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 #include -#include "../../../../../Library/vector3.h" -#include "../../../../../Library/matrix33.h" -#include "../../../../../Library/c2a_math.h" -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/math_constants.h" -#include "../../../../DriverInstances/di_mtq_seiren.h" -#include "../../aocs_manager.h" +#include +#include +#include +#include +#include +#include +#include static MtqSeirenController mtq_seiren_controller_; const MtqSeirenController* const mtq_seiren_controller = &mtq_seiren_controller_; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.h index a9e68c27..0215711f 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.h @@ -14,8 +14,8 @@ #include #include #include -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/ControlUtility/cross_product_control.h" +#include +#include /** * @struct MtqSeirenController diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.c index b23d7fcc..6fd97432 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.c @@ -6,13 +6,13 @@ #include "rw_controller.h" -#include "../../../../../Library/vector3.h" -#include "../../../../../Library/matrix33.h" -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/math_constants.h" +#include +#include +#include +#include #include -#include "../../../../app_registry.h" +#include static void APP_RW_CONTROLLER_init_(void); static void APP_RW_CONTROLLER_exec_(void); diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.h index 4d9d54a0..1f16c4a1 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/rw_controller.h @@ -9,8 +9,8 @@ #include #include #include -#include "../../aocs_manager.h" -#include "../../../../DriverInstances/di_rw0003.h" +#include +#include AppInfo APP_RW_CONTROLLER_create_app(void); diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.c index 522a1b47..c47c0373 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.c @@ -9,8 +9,12 @@ #include #include #include -#include "../../../../DriverInstances/di_mpu9250.h" -#include "../../aocs_manager.h" +#include +#include +#include + +// Satellite Parameters +#include static Mpu9250Filter mpu9250_filter_; const Mpu9250Filter* const mpu9250_filter = &mpu9250_filter_; @@ -128,10 +132,7 @@ static void APP_MPU9250_FILTER_exec_(void) static int APP_MPU9250_FILTER_init_z_filter_mag_(void) { - // カットオフ周波数は今後調整してもよいが今の時点ではこれで進める - mpu9250_filter_.cut_off_freq_lpf_1st_mag_Hz[0] = 0.5f; - mpu9250_filter_.cut_off_freq_lpf_1st_mag_Hz[1] = 0.5f; - mpu9250_filter_.cut_off_freq_lpf_1st_mag_Hz[2] = 0.5f; + VECTOR3_copy(mpu9250_filter_.cut_off_freq_lpf_1st_mag_Hz, MPU9250_PARAMETERS_mag_cut_off_freq_lpf_1st_Hz); C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) @@ -155,11 +156,7 @@ static int APP_MPU9250_FILTER_init_z_filter_mag_(void) static int APP_MPU9250_FILTER_init_z_filter_gyro_(void) { - // カットオフ周波数は今後調整してもよいが今の時点ではこれで進める - // 広帯域制御を狙う場合にはコマンドなどで要調整 - mpu9250_filter_.cut_off_freq_lpf_1st_gyro_Hz[0] = 0.05f; - mpu9250_filter_.cut_off_freq_lpf_1st_gyro_Hz[1] = 0.05f; - mpu9250_filter_.cut_off_freq_lpf_1st_gyro_Hz[2] = 0.05f; + VECTOR3_copy(mpu9250_filter_.cut_off_freq_lpf_1st_gyro_Hz, MPU9250_PARAMETERS_gyro_cut_off_freq_lpf_1st_Hz); C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) @@ -183,13 +180,13 @@ static int APP_MPU9250_FILTER_init_z_filter_gyro_(void) static int APP_MPU9250_FILTER_init_spike_filter_mag_(void) { - // 値は調整してよいが一旦これで進める + for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) { - mpu9250_filter_.spike_filter_config_mag[axis_id].count_limit_to_accept = 3; - mpu9250_filter_.spike_filter_config_mag[axis_id].count_limit_to_reject_continued_warning = 60; - mpu9250_filter_.spike_filter_config_mag[axis_id].reject_threshold = 5000.0; // nT - mpu9250_filter_.spike_filter_config_mag[axis_id].amplitude_limit_to_accept_as_step = 1500.0; // nT + mpu9250_filter_.spike_filter_config_mag[axis_id].count_limit_to_accept = MPU9250_PARAMETERS_mag_spike_count_limit_to_accept[axis_id]; + mpu9250_filter_.spike_filter_config_mag[axis_id].count_limit_to_reject_continued_warning = MPU9250_PARAMETERS_mag_spike_count_limit_to_reject_continued_warning[axis_id]; + mpu9250_filter_.spike_filter_config_mag[axis_id].reject_threshold = MPU9250_PARAMETERS_mag_spike_reject_threshold_nT[axis_id]; + mpu9250_filter_.spike_filter_config_mag[axis_id].amplitude_limit_to_accept_as_step = MPU9250_PARAMETERS_mag_spike_amplitude_limit_to_accept_as_step_nT[axis_id]; } C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; @@ -213,13 +210,12 @@ static int APP_MPU9250_FILTER_init_spike_filter_mag_(void) static int APP_MPU9250_FILTER_init_spike_filter_gyro_(void) { - // 値は調整してよいが一旦これで進める for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) { - mpu9250_filter_.spike_filter_config_gyro[axis_id].count_limit_to_accept = 3; - mpu9250_filter_.spike_filter_config_gyro[axis_id].count_limit_to_reject_continued_warning = 60; - mpu9250_filter_.spike_filter_config_gyro[axis_id].reject_threshold = 0.01; // rad/s - mpu9250_filter_.spike_filter_config_gyro[axis_id].amplitude_limit_to_accept_as_step = 0.005; // rad/s + mpu9250_filter_.spike_filter_config_gyro[axis_id].count_limit_to_accept = MPU9250_PARAMETERS_gyro_spike_count_limit_to_accept[axis_id]; + mpu9250_filter_.spike_filter_config_gyro[axis_id].count_limit_to_reject_continued_warning = MPU9250_PARAMETERS_gyro_spike_count_limit_to_reject_continued_warning[axis_id]; + mpu9250_filter_.spike_filter_config_gyro[axis_id].reject_threshold = MPU9250_PARAMETERS_gyro_spike_reject_threshold_rad_s[axis_id]; + mpu9250_filter_.spike_filter_config_gyro[axis_id].amplitude_limit_to_accept_as_step = MPU9250_PARAMETERS_gyro_spike_amplitude_limit_to_accept_as_step_rad_s[axis_id]; } C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.h index b51da4ad..07b63be3 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/mpu9250_filter.h @@ -8,9 +8,9 @@ #include #include #include -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/SignalProcess/z_filter.h" -#include "../../../../../Library/SignalProcess/spike_filter.h" +#include +#include +#include /** * @enum MPU9250_FILTER_SENSOR_ID diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.c index a14559db..0cdcb5e3 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.c @@ -8,10 +8,13 @@ #include #include #include -#include "../../aocs_manager.h" -#include "../../../../../Library/vector3.h" -#include "../../../../../Library/c2a_math.h" -#include "../../../../../Library/math_constants.h" +#include +#include +#include +#include + +// Satellite Parameters +#include static NanoSsocD60Filter nanossoc_d60_filter_; const NanoSsocD60Filter* const nanossoc_d60_filter = &nanossoc_d60_filter_; @@ -33,10 +36,10 @@ static void APP_NANOSSOC_D60_FILTER_init_(void) VECTOR3_initialize(nanossoc_d60_filter_.sun_vec_est_body, 0.0f); nanossoc_d60_filter_.sun_vec_est_body[2] = 1.0f; // 規格時等にエラーにならない様に,Z軸に1.0fを代入 - nanossoc_d60_filter_.spike_filter_config.count_limit_to_accept = 10; - nanossoc_d60_filter_.spike_filter_config.count_limit_to_reject_continued_warning = 60; - nanossoc_d60_filter_.spike_filter_config.reject_threshold = PHYSICAL_CONST_degree_to_radian(3); - nanossoc_d60_filter_.spike_filter_config.amplitude_limit_to_accept_as_step = PHYSICAL_CONST_degree_to_radian(180); + nanossoc_d60_filter_.spike_filter_config.count_limit_to_accept = NANOSSOC_D60_PARAMETERS_spike_filter_config_count_limit_to_accept; + nanossoc_d60_filter_.spike_filter_config.count_limit_to_reject_continued_warning = NANOSSOC_D60_PARAMETERS_spike_filter_config_count_limit_to_reject_continued_warning; + nanossoc_d60_filter_.spike_filter_config.reject_threshold = NANOSSOC_D60_PARAMETERS_spike_filter_config_reject_threshold_rad; + nanossoc_d60_filter_.spike_filter_config.amplitude_limit_to_accept_as_step =NANOSSOC_D60_PARAMETERS_spike_filter_config_amplitude_limit_to_accept_as_step_rad; C2A_MATH_ERROR filter_setting_result = SPIKE_FILTER_init(&APP_NANOSSOC_D60_FILTER_spike_, nanossoc_d60_filter_.spike_filter_config); diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.h index 454bd6a0..f239ae6b 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/nanossoc_d60_filter.h @@ -8,10 +8,10 @@ #include #include #include -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/SignalProcess/z_filter.h" -#include "../../../../../Library/SignalProcess/spike_filter.h" -#include "../../../../DriverInstances/di_nanossoc_d60.h" +#include +#include +#include +#include /** * @struct NanoSsocD60Filter diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.c index 703dce69..83df6cb3 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.c @@ -9,12 +9,15 @@ #include #include #include -#include "../../../../DriverInstances/di_oem7600.h" -#include "../../aocs_manager.h" -#include "../../../../../Library/vector3.h" -#include "../../../../../Library/matrix33.h" -#include "../../../../../Library/time_space.h" -#include "../../../../../Library/math_constants.h" +#include +#include +#include +#include +#include +#include + +// Satellite Parameters +#include #define OEM7600_FILTER_POS_VEL_SIX_DIM (6) @@ -117,18 +120,17 @@ static void APP_OEM7600_FILTER_exec_(void) static int APP_OEM7600_FILTER_init_spike_filter_(void) { - // 値は調整してよいが一旦これで進める for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) { - oem7600_filter_.position_spike_filter_config[axis_id].count_limit_to_accept = 3; - oem7600_filter_.position_spike_filter_config[axis_id].count_limit_to_reject_continued_warning = 60; - oem7600_filter_.position_spike_filter_config[axis_id].reject_threshold = 10000.0; // m - oem7600_filter_.position_spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = 8000.0; // m - - oem7600_filter_.velocity_spike_filter_config[axis_id].count_limit_to_accept = 3; - oem7600_filter_.velocity_spike_filter_config[axis_id].count_limit_to_reject_continued_warning = 60; - oem7600_filter_.velocity_spike_filter_config[axis_id].reject_threshold = 1000.0; // m/s - oem7600_filter_.velocity_spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = 100; // m/s + oem7600_filter_.position_spike_filter_config[axis_id].count_limit_to_accept = OEM7600_PARAMETERS_position_spike_filter_config_count_limit_to_accept[axis_id]; + oem7600_filter_.position_spike_filter_config[axis_id].count_limit_to_reject_continued_warning = OEM7600_PARAMETERS_position_spike_filter_config_count_limit_to_reject_continued_warning[axis_id]; + oem7600_filter_.position_spike_filter_config[axis_id].reject_threshold = OEM7600_PARAMETERS_position_spike_filter_config_reject_threshold_m[axis_id]; + oem7600_filter_.position_spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = OEM7600_PARAMETERS_position_spike_filter_config_amplitude_limit_to_accept_as_step_m[axis_id]; + + oem7600_filter_.velocity_spike_filter_config[axis_id].count_limit_to_accept = OEM7600_PARAMETERS_velocity_spike_filter_config_count_limit_to_accept[axis_id]; + oem7600_filter_.velocity_spike_filter_config[axis_id].count_limit_to_reject_continued_warning = OEM7600_PARAMETERS_velocity_spike_filter_config_count_limit_to_reject_continued_warning[axis_id]; + oem7600_filter_.velocity_spike_filter_config[axis_id].reject_threshold = OEM7600_PARAMETERS_velocity_spike_filter_config_reject_threshold_m_s[axis_id]; + oem7600_filter_.velocity_spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = OEM7600_PARAMETERS_velocity_spike_filter_config_amplitude_limit_to_accept_as_step_m_s[axis_id]; } C2A_MATH_ERROR position_filter_setting_result = C2A_MATH_ERROR_OK; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.h index e1b0599d..0eec082a 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/oem7600_filter.h @@ -8,8 +8,8 @@ #include #include #include -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/SignalProcess/spike_filter.h" +#include +#include /** * @struct Oem7600Filter diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.c index e00b717e..62bcb90b 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.c @@ -9,7 +9,10 @@ #include #include #include -#include "../../aocs_manager.h" +#include + +// Satellite Parameters +#include static Rm3100Filter rm3100_filter_; const Rm3100Filter* const rm3100_filter = &rm3100_filter_; @@ -20,12 +23,12 @@ static SpikeFilter APP_RM3100_FILTER_spike_[RM3100_IDX_MAX][PHYSICAL_CONST_THREE static void APP_RM3100_FILTER_init_(void); static void APP_RM3100_FILTER_exec_(void); -static int APP_RM3100_FILTER_init_z_filter_(RM3100_IDX rm3100_id, float cut_off_freq_Hz); +static int APP_RM3100_FILTER_init_z_filter_(RM3100_IDX rm3100_id, const float cut_off_freq_Hz[PHYSICAL_CONST_THREE_DIM]); static int APP_RM3100_FILTER_init_spike_filter_(RM3100_IDX rm3100_id, - uint8_t count_limit_to_accept, - uint8_t count_limit_to_reject_continued_warning, - double reject_threshold_nT, - double amplitude_limit_to_accept_as_step_nT); + const uint8_t count_limit_to_accept[PHYSICAL_CONST_THREE_DIM], + const uint8_t count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM], + const float reject_threshold_nT[PHYSICAL_CONST_THREE_DIM], + const float amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM]); AppInfo APP_RM3100_FILTER_create_app(void) { @@ -35,30 +38,36 @@ AppInfo APP_RM3100_FILTER_create_app(void) static void APP_RM3100_FILTER_init_(void) { // same sampling frequency is applied to all filters - // (since the frequency must be coincide with the call interval of this apllication) + // (since the frequency must be coincide with the call interval of this application) rm3100_filter_.sampling_freq_Hz = 10.0f; - int z_filter_aobc_init_result = APP_RM3100_FILTER_init_z_filter_(RM3100_IDX_ON_AOBC, 0.5f); + int z_filter_aobc_init_result = APP_RM3100_FILTER_init_z_filter_(RM3100_IDX_ON_AOBC, RM3100_PARAMETERS_mag_aobc_cut_off_freq_lpf_1st_Hz); if (z_filter_aobc_init_result != 0) { Printf("RM3100 on AOBC ZFilter init Failed ! \n"); } - int z_filter_external_init_result = APP_RM3100_FILTER_init_z_filter_(RM3100_IDX_EXTERNAL, 0.5f); + int z_filter_external_init_result = APP_RM3100_FILTER_init_z_filter_(RM3100_IDX_EXTERNAL, RM3100_PARAMETERS_mag_ext_cut_off_freq_lpf_1st_Hz); if (z_filter_external_init_result != 0) { Printf("RM3100 external ZFilter init Failed ! \n"); } int spike_filter_aobc_init_result = APP_RM3100_FILTER_init_spike_filter_(RM3100_IDX_ON_AOBC, - 3, 60, 5000.0, 1500.0); + RM3100_PARAMETERS_mag_aobc_spike_count_limit_to_accept, + RM3100_PARAMETERS_mag_aobc_spike_count_limit_to_reject_continued_warning, + RM3100_PARAMETERS_mag_aobc_spike_reject_threshold_nT, + RM3100_PARAMETERS_mag_aobc_spike_amplitude_limit_to_accept_as_step_nT); if (spike_filter_aobc_init_result != 0) { Printf("RM3100 on AOBC SpikeFilter init Failed ! \n"); } int spike_filter_external_init_result = APP_RM3100_FILTER_init_spike_filter_(RM3100_IDX_EXTERNAL, - 3, 60, 5000.0, 1500.0); + RM3100_PARAMETERS_mag_ext_spike_count_limit_to_accept, + RM3100_PARAMETERS_mag_ext_spike_count_limit_to_reject_continued_warning, + RM3100_PARAMETERS_mag_ext_spike_reject_threshold_nT, + RM3100_PARAMETERS_mag_ext_spike_amplitude_limit_to_accept_as_step_nT); if (spike_filter_external_init_result != 0) { Printf("RM3100 external SpikeFilter init Failed ! \n"); @@ -114,11 +123,11 @@ static void APP_RM3100_FILTER_exec_(void) return; } -static int APP_RM3100_FILTER_init_z_filter_(RM3100_IDX rm3100_id, float cut_off_freq_Hz) +static int APP_RM3100_FILTER_init_z_filter_(RM3100_IDX rm3100_id, const float cut_off_freq_Hz[PHYSICAL_CONST_THREE_DIM]) { for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) { - rm3100_filter_.cut_off_freq_lpf_1st_Hz[rm3100_id][axis_id] = cut_off_freq_Hz; + rm3100_filter_.cut_off_freq_lpf_1st_Hz[rm3100_id][axis_id] = cut_off_freq_Hz[axis_id]; } C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; @@ -144,20 +153,20 @@ static int APP_RM3100_FILTER_init_z_filter_(RM3100_IDX rm3100_id, float cut_off_ } static int APP_RM3100_FILTER_init_spike_filter_(RM3100_IDX rm3100_id, - uint8_t count_limit_to_accept, - uint8_t count_limit_to_reject_continued_warning, - double reject_threshold_nT, - double amplitude_limit_to_accept_as_step_nT) + const uint8_t count_limit_to_accept[PHYSICAL_CONST_THREE_DIM], + const uint8_t count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM], + const float reject_threshold_nT[PHYSICAL_CONST_THREE_DIM], + const float amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM]) { for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) { rm3100_filter_.spike_filter_config[rm3100_id][axis_id].count_limit_to_accept = - count_limit_to_accept; + count_limit_to_accept[axis_id]; rm3100_filter_.spike_filter_config[rm3100_id][axis_id].count_limit_to_reject_continued_warning = - count_limit_to_reject_continued_warning; - rm3100_filter_.spike_filter_config[rm3100_id][axis_id].reject_threshold = reject_threshold_nT; + count_limit_to_reject_continued_warning[axis_id]; + rm3100_filter_.spike_filter_config[rm3100_id][axis_id].reject_threshold = reject_threshold_nT[axis_id]; rm3100_filter_.spike_filter_config[rm3100_id][axis_id].amplitude_limit_to_accept_as_step = - amplitude_limit_to_accept_as_step_nT; + amplitude_limit_to_accept_as_step_nT[axis_id]; } C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.h index e9f8d102..a6e8a2e2 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rm3100_filter.h @@ -8,10 +8,10 @@ #include #include #include -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/SignalProcess/z_filter.h" -#include "../../../../../Library/SignalProcess/spike_filter.h" -#include "../../../../DriverInstances/di_rm3100.h" +#include +#include +#include +#include /** * @struct Rm3100Filter diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.c index 9c71e1a4..8f5b7248 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.c @@ -9,7 +9,10 @@ #include #include #include -#include "../../aocs_manager.h" +#include + +// Satellite Parameters +#include static Rw0003Filter rw0003_filter_; const Rw0003Filter* const rw0003_filter = &rw0003_filter_; @@ -29,11 +32,10 @@ static void APP_RW0003_FILTER_init_(void) for (uint8_t axis_id = 0; axis_id < RW0003_IDX_MAX; axis_id++) { rw0003_filter_.filter_error[axis_id] = C2A_MATH_ERROR_OK; - // 値は調整してよいが一旦これで進める - rw0003_filter_.spike_filter_config[axis_id].count_limit_to_accept = 3; - rw0003_filter_.spike_filter_config[axis_id].count_limit_to_reject_continued_warning = 10; - rw0003_filter_.spike_filter_config[axis_id].reject_threshold = 50.0; // rad/s - rw0003_filter_.spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = 25.0; // rad/s + rw0003_filter_.spike_filter_config[axis_id].count_limit_to_accept = RW0003_PARAMETERS_spike_filter_config_count_limit_to_accept[axis_id]; + rw0003_filter_.spike_filter_config[axis_id].count_limit_to_reject_continued_warning = RW0003_PARAMETERS_spike_filter_config_count_limit_to_reject_continued_warning[axis_id]; + rw0003_filter_.spike_filter_config[axis_id].reject_threshold = RW0003_PARAMETERS_spike_filter_config_reject_threshold_rad_s[axis_id]; + rw0003_filter_.spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = RW0003_PARAMETERS_spike_filter_config_amplitude_limit_to_accept_as_step_rad_s[axis_id]; C2A_MATH_ERROR ret = SPIKE_FILTER_init(&APP_RW0003_FILTER_spike_[axis_id], rw0003_filter_.spike_filter_config[axis_id]); if (ret != C2A_MATH_ERROR_OK) diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.h index ab871463..ee08f5ed 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/rw0003_filter.h @@ -8,9 +8,9 @@ #include #include #include -#include "../../../../DriverInstances/di_rw0003.h" -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/SignalProcess/spike_filter.h" +#include +#include +#include /** * @struct Rw0003Filter diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.c index 08652323..10ec4767 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.c @@ -9,9 +9,12 @@ #include #include #include -#include "../../../../DriverInstances/di_sagitta.h" -#include "../../aocs_manager.h" -#include "../../../../../Library/physical_constants.h" +#include +#include +#include + +// Satellite Parameters +#include static SagittaFilter sagitta_filter_; const SagittaFilter* const sagitta_filter = &sagitta_filter_; @@ -78,13 +81,10 @@ static void APP_SAGITTA_FILTER_exec_(void) static int APP_SAGITTA_FILTER_init_spike_filter_(void) { - // 値は調整してよいが一旦これで進める - sagitta_filter_.q_i2b_spike_filter_config.count_limit_to_accept = 20; - sagitta_filter_.q_i2b_spike_filter_config.count_limit_to_reject_continued_warning = 200; - sagitta_filter_.q_i2b_spike_filter_config.reject_threshold = - PHYSICAL_CONST_degree_to_radian(1.0f); - sagitta_filter_.q_i2b_spike_filter_config.amplitude_limit_to_accept_as_step = - PHYSICAL_CONST_degree_to_radian(0.6f); // STT精度は8.7 [秒角(1σ)] + sagitta_filter_.q_i2b_spike_filter_config.count_limit_to_accept = SAGITTA_PARAMETERS_q_i2b_spike_filter_config_count_limit_to_accept; + sagitta_filter_.q_i2b_spike_filter_config.count_limit_to_reject_continued_warning = SAGITTA_PARAMETERS_q_i2b_spike_filter_config_count_limit_to_reject_continued_warning; + sagitta_filter_.q_i2b_spike_filter_config.reject_threshold = SAGITTA_PARAMETERS_q_i2b_spike_filter_config_reject_threshold_rad; + sagitta_filter_.q_i2b_spike_filter_config.amplitude_limit_to_accept_as_step = SAGITTA_PARAMETERS_q_i2b_spike_filter_config_amplitude_limit_to_accept_as_step_rad; C2A_MATH_ERROR q_i2b_spike_filter_setting_result = C2A_MATH_ERROR_OK; C2A_MATH_ERROR filter_setting_result = diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.h index 14e49e0f..80236cba 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/sagitta_filter.h @@ -7,8 +7,8 @@ #include #include -#include "../../../../../Library/SignalProcess/spike_filter.h" -#include "../../../../../Library/quaternion.h" +#include +#include /** * @struct SagittaFilter diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.c index 18392076..d717f70d 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.c @@ -9,7 +9,11 @@ #include #include #include -#include "../../../../DriverInstances/di_stim210.h" +#include +#include + +//Satellite Parameters +#include static Stim210Filter stim210_filter_; const Stim210Filter* const stim210_filter = &stim210_filter_; @@ -85,10 +89,7 @@ static void APP_STIM210_FILTER_exec_(void) static int APP_STIM210_FILTER_init_z_filter_(void) { - // 値は調整してよいが一旦これで進める - stim210_filter_.cut_off_freq_lpf_1st_Hz[0] = 1.0f; - stim210_filter_.cut_off_freq_lpf_1st_Hz[1] = 1.0f; - stim210_filter_.cut_off_freq_lpf_1st_Hz[2] = 1.0f; + VECTOR3_copy(stim210_filter_.cut_off_freq_lpf_1st_Hz, STIM210_PARAMETERS_gyro_cut_off_freq_lpf_1st_Hz); C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) @@ -114,13 +115,12 @@ static int APP_STIM210_FILTER_init_z_filter_(void) static int APP_STIM210_FILTER_init_spike_filter_(void) { - // 値は調整してよいが一旦これで進める for (uint8_t axis_id = 0; axis_id < PHYSICAL_CONST_THREE_DIM; axis_id++) { - stim210_filter_.spike_filter_config[axis_id].count_limit_to_accept = 3; - stim210_filter_.spike_filter_config[axis_id].count_limit_to_reject_continued_warning = 60; - stim210_filter_.spike_filter_config[axis_id].reject_threshold = 0.01; // rad/s - stim210_filter_.spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = 0.002; // rad/s + stim210_filter_.spike_filter_config[axis_id].count_limit_to_accept = STIM210_PARAMETERS_gyro_spike_count_limit_to_accept[axis_id]; + stim210_filter_.spike_filter_config[axis_id].count_limit_to_reject_continued_warning = STIM210_PARAMETERS_gyro_spike_count_limit_to_reject_continued_warning[axis_id]; + stim210_filter_.spike_filter_config[axis_id].reject_threshold = STIM210_PARAMETERS_gyro_spike_reject_threshold_rad_s[axis_id]; + stim210_filter_.spike_filter_config[axis_id].amplitude_limit_to_accept_as_step = STIM210_PARAMETERS_gyro_spike_amplitude_limit_to_accept_as_step_rad_s[axis_id]; } C2A_MATH_ERROR filter_setting_result_three_axis = C2A_MATH_ERROR_OK; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.h index ee9ffafd..e9cca0f9 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorFilters/stim210_filter.h @@ -8,9 +8,9 @@ #include #include #include -#include "../../../../../Library/physical_constants.h" -#include "../../../../../Library/SignalProcess/z_filter.h" -#include "../../../../../Library/SignalProcess/spike_filter.h" +#include +#include +#include /** * @struct Stim210Filter diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.c index c8ad8146..240ace03 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.c @@ -8,7 +8,10 @@ #include #include -#include "../../../Power/power_switch_control.h" +#include + +// Satellite Parameters +#include static CurrentAnomaly current_anomaly_; const CurrentAnomaly* const current_anomaly = ¤t_anomaly_; @@ -30,27 +33,27 @@ AppInfo APP_CURRENT_ANOMALY_create_app(void) static void APP_CURRENT_ANOMALY_init_(void) { - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_PIC] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_STIM210] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_SAGITTA] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_OEM7600] = 1.0; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RM3100] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_NANOSSOC_D60] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_MTQ] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RW0003_X] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RW0003_Y] = 0.5; - current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RW0003_Z] = 0.5; - - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_PIC] = 200; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_STIM210] = 1000; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_SAGITTA] = 500; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_OEM7600] = 1000; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RM3100] = 200; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_NANOSSOC_D60] = 150; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_MTQ] = 2000; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RW0003_X] = 2000; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RW0003_Y] = 2000; - current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RW0003_Z] = 2000; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_PIC] = FDIR_PARAMETERS_hw_oc_detection_threshold_pic_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_STIM210] = FDIR_PARAMETERS_hw_oc_detection_threshold_stim210_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_SAGITTA] = FDIR_PARAMETERS_hw_oc_detection_threshold_sagitta_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_OEM7600] = FDIR_PARAMETERS_hw_oc_detection_threshold_oem7600_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RM3100] = FDIR_PARAMETERS_hw_oc_detection_threshold_rm3100_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_NANOSSOC_D60] = FDIR_PARAMETERS_hw_oc_detection_threshold_nanossoc_d60_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_MTQ] = FDIR_PARAMETERS_hw_oc_detection_threshold_mtq_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RW0003_X] = FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_x_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RW0003_Y] = FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_y_V; + current_anomaly_.hw_oc_event_logger_threshold_V[INA260_IDX_RW0003_Z] = FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_z_V; + + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_PIC] = FDIR_PARAMETERS_sw_oc_threshold_pic_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_STIM210] = FDIR_PARAMETERS_sw_oc_threshold_stim210_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_SAGITTA] = FDIR_PARAMETERS_sw_oc_threshold_sagitta_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_OEM7600] = FDIR_PARAMETERS_sw_oc_threshold_oem7600_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RM3100] = FDIR_PARAMETERS_sw_oc_threshold_rm3100_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_NANOSSOC_D60] = FDIR_PARAMETERS_sw_oc_threshold_nanossoc_d60_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_MTQ] = FDIR_PARAMETERS_sw_oc_threshold_mtq_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RW0003_X] = FDIR_PARAMETERS_sw_oc_threshold_rw0003_x_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RW0003_Y] = FDIR_PARAMETERS_sw_oc_threshold_rw0003_y_mA; + current_anomaly_.sw_oc_threshold_mA[INA260_IDX_RW0003_Z] = FDIR_PARAMETERS_sw_oc_threshold_rw0003_z_mA; return; } diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.h b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.h index 4a9b84a8..9dfba53e 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.h +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorMonitors/current_anomaly.h @@ -7,7 +7,7 @@ #include #include -#include "../../../../DriverInstances/di_ina260.h" +#include /** * @struct CurrentAnomaly diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gpsr_selector.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gpsr_selector.c index a87e8dba..f08c1205 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gpsr_selector.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gpsr_selector.c @@ -8,8 +8,8 @@ #include "gpsr_selector.h" #include -#include "../../../../DriverInstances/di_oem7600.h" -#include "../../aocs_manager.h" +#include +#include static GpsrSelector gpsr_selector_; const GpsrSelector* const gpsr_selector = &gpsr_selector_; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gyro_selector.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gyro_selector.c index 624cc642..e405cd61 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gyro_selector.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gyro_selector.c @@ -9,11 +9,11 @@ #include #include -#include "../../../../DriverInstances/di_mpu9250.h" -#include "../../../../DriverInstances/di_stim210.h" -#include "../SensorFilters/mpu9250_filter.h" -#include "../SensorFilters/stim210_filter.h" -#include "../../aocs_manager.h" +#include +#include +#include +#include +#include static GyroSelector gyro_selector_; const GyroSelector* const gyro_selector = &gyro_selector_; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.c index 544d2ca9..198c203a 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.c @@ -8,11 +8,14 @@ #include #include -#include "../../../../DriverInstances/di_mpu9250.h" -#include "../../../../DriverInstances/di_rm3100.h" -#include "../SensorFilters/mpu9250_filter.h" -#include "../SensorFilters/rm3100_filter.h" -#include "../../aocs_manager.h" +#include +#include +#include +#include +#include + +// Satellite Parameters +#include static MagnetometerSelector magnetometer_selector_; const MagnetometerSelector* const magnetometer_selector = &magnetometer_selector_; @@ -30,7 +33,7 @@ AppInfo APP_MAG_SELECTOR_create_app(void) static void APP_MAG_SELECTOR_init_(void) { - magnetometer_selector_.state = APP_MAG_SELECTOR_STATE_RM_EXT; + magnetometer_selector_.state = COMPONENT_SELECTOR_PARAMETERS_initial_selected_magnetometer; magnetometer_selector_.auto_flag = 0; return; } diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/stt_selector.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/stt_selector.c index 0b9d6260..7d625daf 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/stt_selector.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/stt_selector.c @@ -8,8 +8,8 @@ #include "stt_selector.h" #include -#include "../../../../DriverInstances/di_sagitta.h" -#include "../../aocs_manager.h" +#include +#include static SttSelector stt_selector_; const SttSelector* const stt_selector = &stt_selector_; diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/sun_sensor_selector.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/sun_sensor_selector.c index 013f1b7b..1750cd5b 100644 --- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/sun_sensor_selector.c +++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/sun_sensor_selector.c @@ -9,8 +9,11 @@ #include #include #include -#include "../../../../DriverInstances/di_nanossoc_d60.h" -#include "../../aocs_manager.h" +#include +#include + +// Satellite Parameters +#include static SunSensorSelector sun_sensor_selector_; const SunSensorSelector* const sun_sensor_selector = &sun_sensor_selector_; @@ -43,8 +46,8 @@ AppInfo APP_SS_SELECTOR_create_app(void) static void APP_SS_SELECTOR_init_(void) { - sun_sensor_selector_.sun_intensity_lower_threshold_percent = 80.0; - sun_sensor_selector_.sun_intensity_upper_threshold_percent = 120.0; + sun_sensor_selector_.sun_intensity_lower_threshold_percent = NANOSSOC_D60_PARAMETERS_sun_intensity_lower_threshold_percent; + sun_sensor_selector_.sun_intensity_upper_threshold_percent = NANOSSOC_D60_PARAMETERS_sun_intensity_upper_threshold_percent; for (int idx = 0; idx < NANOSSOC_D60_IDX_MAX; idx++) { APP_SS_SELECTOR_available_sun_sensor_list_[idx] = NANOSSOC_D60_IDX_MAX; diff --git a/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_geomag_calculator.c b/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_geomag_calculator.c index 9a085d42..c3472141 100644 --- a/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_geomag_calculator.c +++ b/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_geomag_calculator.c @@ -5,13 +5,13 @@ */ #include "inertial_geomag_calculator.h" -#include "../aocs_manager.h" -#include "../../../../Library/matrix33.h" -#include "../../../../Library/time_space.h" -#include "../../../../Library/geomagnetism.h" +#include +#include +#include +#include #include -#include "../../../app_registry.h" +#include static InertialGeomagCalculator inertial_geomag_calulator_; diff --git a/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_sun_direction_calculator.c b/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_sun_direction_calculator.c index 79aebe8f..46544417 100644 --- a/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_sun_direction_calculator.c +++ b/src/src_user/Applications/UserDefined/AOCS/InertialReference/inertial_sun_direction_calculator.c @@ -5,8 +5,8 @@ */ #include "inertial_sun_direction_calculator.h" -#include "../aocs_manager.h" -#include "../../../../Library/time_space.h" +#include +#include static void APP_SUN_DIR_ECI_CALC_init_(void); diff --git a/src/src_user/Applications/UserDefined/AOCS/InertialReference/time_space_calculator.c b/src/src_user/Applications/UserDefined/AOCS/InertialReference/time_space_calculator.c index f4a86fa7..dfb2ed48 100644 --- a/src/src_user/Applications/UserDefined/AOCS/InertialReference/time_space_calculator.c +++ b/src/src_user/Applications/UserDefined/AOCS/InertialReference/time_space_calculator.c @@ -9,9 +9,9 @@ #include #include #include -#include "../aocs_manager.h" -#include "../../../../Library/time_space.h" -#include "../../../../Library/c2a_math.h" +#include +#include +#include static TimeSpaceCalculator time_space_calculator_; diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.c b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.c index 078ca703..7bda2c8d 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.c +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.c @@ -9,12 +9,15 @@ #include #include #include "kepler_orbit_propagator.h" -#include "../aocs_manager.h" -#include "../../../../Library/math_constants.h" -#include "../../../../Library/matrix33.h" -#include "../../../../Library/time_space.h" +#include +#include +#include +#include #include +// SatelliteParameters +#include + static GpsrOrbitPropagator gpsr_orbit_propagator_; const GpsrOrbitPropagator* const gpsr_orbit_propagator = &gpsr_orbit_propagator_; @@ -39,19 +42,19 @@ static void APP_GPSROP_init_(void) memset(&gpsr_orbit_propagator_, 0x00, sizeof(GpsrOrbitPropagator)); // ひとまず初期値はS2E_ISSL6U_AOCSの軌道設定に合わせる - gpsr_orbit_propagator_.orbital_elements.semi_major_axis_km = 6794.5f; - gpsr_orbit_propagator_.orbital_elements.eccentricity = 0.0015f; - gpsr_orbit_propagator_.orbital_elements.inclination_rad = 0.9012f; - gpsr_orbit_propagator_.orbital_elements.raan_rad = 0.1411f; - gpsr_orbit_propagator_.orbital_elements.arg_perigee_rad = 0.0f; // 最終書き込み確認用に1.7952fから変更 - gpsr_orbit_propagator_.orbital_elements.epoch_jday = 2.458940966402607e6; - - gpsr_orbit_propagator_.orbital_elements_threshold.semi_major_axis_km = 50.0f; - gpsr_orbit_propagator_.orbital_elements_threshold.eccentricity = 0.1f; - gpsr_orbit_propagator_.orbital_elements_threshold.inclination_rad = PHYSICAL_CONST_degree_to_radian(20.0f); - gpsr_orbit_propagator_.orbital_elements_threshold.raan_rad = PHYSICAL_CONST_degree_to_radian(20.0f); - gpsr_orbit_propagator_.orbital_elements_threshold.arg_perigee_rad = PHYSICAL_CONST_degree_to_radian(50.0f); - gpsr_orbit_propagator_.orbital_elements_threshold.epoch_jday = 0.1; + gpsr_orbit_propagator_.orbital_elements.semi_major_axis_km = ORBIT_PARAMETERS_gpsr_semi_major_axis_km; + gpsr_orbit_propagator_.orbital_elements.eccentricity = ORBIT_PARAMETERS_gpsr_eccentricity; + gpsr_orbit_propagator_.orbital_elements.inclination_rad = ORBIT_PARAMETERS_gpsr_inclination_rad; + gpsr_orbit_propagator_.orbital_elements.raan_rad = ORBIT_PARAMETERS_gpsr_raan_rad; + gpsr_orbit_propagator_.orbital_elements.arg_perigee_rad = ORBIT_PARAMETERS_gpsr_arg_perigee_rad; + gpsr_orbit_propagator_.orbital_elements.epoch_jday = ORBIT_PARAMETERS_gpsr_epoch_jday; + + gpsr_orbit_propagator_.orbital_elements_threshold.semi_major_axis_km = ORBIT_PARAMETERS_gpsr_threshold_semi_major_axis_km; + gpsr_orbit_propagator_.orbital_elements_threshold.eccentricity = ORBIT_PARAMETERS_gpsr_threshold_eccentricity; + gpsr_orbit_propagator_.orbital_elements_threshold.inclination_rad = ORBIT_PARAMETERS_gpsr_threshold_inclination_rad; + gpsr_orbit_propagator_.orbital_elements_threshold.raan_rad = ORBIT_PARAMETERS_gpsr_threshold_raan_rad; + gpsr_orbit_propagator_.orbital_elements_threshold.arg_perigee_rad =ORBIT_PARAMETERS_gpsr_threshold_arg_perigee_rad; + gpsr_orbit_propagator_.orbital_elements_threshold.epoch_jday = ORBIT_PARAMETERS_gpsr_threshold_epoch_jday; KEPLER_ORBIT_init_constants(&gpsr_orbit_propagator_.orbit_constants, gpsr_orbit_propagator_.orbital_elements); diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.h b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.h index 028971c5..101e0421 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.h +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/gpsr_orbit_propagator.h @@ -7,7 +7,7 @@ #include #include -#include "../../../../Library/Orbit/kepler_orbit.h" +#include /** * @struct GpsrOrbitPropagator diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.c b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.c index cef4532f..e2db10c0 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.c +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.c @@ -8,11 +8,14 @@ #include #include #include -#include "../aocs_manager.h" -#include "../../../../Library/matrix33.h" -#include "../../../../Library/time_space.h" +#include +#include +#include #include +// SatelliteParameters +#include + static KeplerOrbitPropagator kepler_orbit_propagator_; const KeplerOrbitPropagator* const kepler_orbit_propagator = &kepler_orbit_propagator_; @@ -28,12 +31,12 @@ static void APP_KOP_init_(void) { memset(&kepler_orbit_propagator_, 0x00, sizeof(KeplerOrbitPropagator)); - kepler_orbit_propagator_.orbital_elements.semi_major_axis_km = 6899.3234f; - kepler_orbit_propagator_.orbital_elements.eccentricity = 4.86396e-4f; - kepler_orbit_propagator_.orbital_elements.inclination_rad = PHYSICAL_CONST_degree_to_radian(97.50372f); - kepler_orbit_propagator_.orbital_elements.raan_rad = PHYSICAL_CONST_degree_to_radian(340.20189f); - kepler_orbit_propagator_.orbital_elements.arg_perigee_rad = PHYSICAL_CONST_degree_to_radian(221.60537f); - kepler_orbit_propagator_.orbital_elements.epoch_jday = 2.459931936719433e6; + kepler_orbit_propagator_.orbital_elements.semi_major_axis_km = ORBIT_PARAMETERS_kepler_semi_major_axis_km; + kepler_orbit_propagator_.orbital_elements.eccentricity = ORBIT_PARAMETERS_kepler_eccentricity; + kepler_orbit_propagator_.orbital_elements.inclination_rad = ORBIT_PARAMETERS_kepler_inclination_rad; + kepler_orbit_propagator_.orbital_elements.raan_rad = ORBIT_PARAMETERS_kepler_raan_rad; + kepler_orbit_propagator_.orbital_elements.arg_perigee_rad = ORBIT_PARAMETERS_kepler_arg_perigee_rad; + kepler_orbit_propagator_.orbital_elements.epoch_jday = ORBIT_PARAMETERS_kepler_epoch_jday; KEPLER_ORBIT_init_constants(&kepler_orbit_propagator_.orbit_constants, kepler_orbit_propagator_.orbital_elements); diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.h b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.h index f04d24ea..148db82a 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.h +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/kepler_orbit_propagator.h @@ -7,7 +7,7 @@ #include #include -#include "../../../../Library/Orbit/kepler_orbit.h" +#include /** * @struct KeplerOrbitPropagator diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.c b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.c index 4f48d657..ac393e40 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.c +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.c @@ -14,15 +14,15 @@ #include #include #include -#include "../../../app_registry.h" +#include #include -#include "../aocs_manager.h" -#include "../../../../Library/vector3.h" -#include "../../../../Library/matrix33.h" -#include "../../../../Library/time_space.h" +#include +#include +#include +#include // SatelliteParameters -#include "../../../../Settings/SatelliteParameters/orbit_parameters.h" +#include static OrbitCalculator orbit_calculator_; const OrbitCalculator* const orbit_calculator = &orbit_calculator_; diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.h b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.h index 3789e0a2..3ce7b6da 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.h +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/orbit_calculator.h @@ -7,7 +7,7 @@ #include #include -#include "../../../../Library/Orbit/kepler_orbit.h" +#include /** * @enum APP_ORBIT_CALC_METHOD diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.c b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.c index 379e7c2f..faff6ff9 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.c +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.c @@ -9,12 +9,15 @@ #include #include #include -#include "../../../app_registry.h" -#include "../aocs_manager.h" -#include "../../../../Library/matrix33.h" -#include "../../../../Library/time_space.h" +#include +#include +#include +#include #include +// SatelliteParameters +#include + // #define APP_SGP4_DEBUG_OUTPUT //!< デバッグ出力を表示させたいときに定義する static Sgp4OrbitPropagator sgp4_orbit_propagator_; @@ -33,16 +36,16 @@ static void APP_SGP4_init_(void) memset(&sgp4_orbit_propagator_, 0x00, sizeof(Sgp4OrbitPropagator)); // 1行目 - sgp4_orbit_propagator_.tle_input.epoch_year = 22; - sgp4_orbit_propagator_.tle_input.epoch_day = 352.00000000; - sgp4_orbit_propagator_.tle_input.b_star = 0.0f; + sgp4_orbit_propagator_.tle_input.epoch_year = ORBIT_PARAMETERS_tle_epoch_year; + sgp4_orbit_propagator_.tle_input.epoch_day = ORBIT_PARAMETERS_tle_epoch_day; + sgp4_orbit_propagator_.tle_input.b_star = ORBIT_PARAMETERS_tle_b_star; // 2行目 - sgp4_orbit_propagator_.tle_input.inclination_deg = 97.5068f; - sgp4_orbit_propagator_.tle_input.raan_deg = 339.7118f; - sgp4_orbit_propagator_.tle_input.eccentricity = 0.0011775f; - sgp4_orbit_propagator_.tle_input.arg_perigee_deg = 245.9837f; - sgp4_orbit_propagator_.tle_input.mean_anomaly_deg = 114.0163f; - sgp4_orbit_propagator_.tle_input.mean_motion_rpd = 15.15782335f; + sgp4_orbit_propagator_.tle_input.inclination_deg = ORBIT_PARAMETERS_tle_inclination_deg; + sgp4_orbit_propagator_.tle_input.raan_deg = ORBIT_PARAMETERS_tle_raan_deg; + sgp4_orbit_propagator_.tle_input.eccentricity = ORBIT_PARAMETERS_tle_eccentricity; + sgp4_orbit_propagator_.tle_input.arg_perigee_deg = ORBIT_PARAMETERS_tle_arg_perigee_deg; + sgp4_orbit_propagator_.tle_input.mean_anomaly_deg = ORBIT_PARAMETERS_tle_mean_anomaly_deg; + sgp4_orbit_propagator_.tle_input.mean_motion_rpd = ORBIT_PARAMETERS_tle_mean_motion_rpd; #ifdef APP_SGP4_DEBUG_OUTPUT uint32_t start_time_ms = (uint32_t)TMGR_get_master_total_cycle_in_msec(); diff --git a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.h b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.h index 9e54ff3d..97503b3e 100644 --- a/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.h +++ b/src/src_user/Applications/UserDefined/AOCS/OrbitEstimation/sgp4_orbit_propagator.h @@ -7,7 +7,7 @@ #include #include -#include "../../../../Library/Orbit/sgp4.h" +#include /** * @struct Sgp4OrbitPropagator diff --git a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.c b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.c index e0566ab7..ca4cbbcc 100644 --- a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.c +++ b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.c @@ -7,10 +7,10 @@ #include #include #include -#include "../../../app_registry.h" +#include #include "quaternion_interpolator.h" -#include "../aocs_manager.h" +#include static QuaternionInterpolator quaternion_interpolator_; const QuaternionInterpolator* const quaternion_interpolator = &quaternion_interpolator_; diff --git a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.h b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.h index f7c153cf..fd76fe0e 100644 --- a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.h +++ b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/quaternion_interpolator.h @@ -8,7 +8,7 @@ #include #include #include -#include "../../../../Library/quaternion.h" +#include #define APP_QI_TARGET_MAX (20) // 衛星が確保可能な目標Quaternionの数 diff --git a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.c b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.c index c40e0a91..db614ecf 100644 --- a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.c +++ b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.c @@ -12,9 +12,12 @@ #include "target_attitude_calculator.h" #include "quaternion_interpolator.h" #include "target_attitude_from_orbit.h" -#include "../aocs_manager.h" -#include "../../../app_registry.h" -#include "../../../../Library/vector3.h" +#include +#include +#include + +// SatelliteParameters +#include static TargetAttitudeCalculator target_attitude_calculator_; const TargetAttitudeCalculator* const target_attitude_calculator = &target_attitude_calculator_; @@ -46,8 +49,8 @@ AppInfo APP_TARGET_ATT_CALC_create_app(void) static void APP_TARGET_ATT_CALC_init_(void) { // デフォルトはMANUALモード - target_attitude_calculator_.mode = APP_TARGET_ATT_CALC_MODE_MANUAL; - target_attitude_calculator_.quaternion_target_i2t = QUATERNION_make_unit(); + target_attitude_calculator_.mode = ATTITUDE_TARGET_PARAMETERS_mode; + target_attitude_calculator_.quaternion_target_i2t = ATTITUDE_TARGET_PARAMETERS_quaternion_target_i2t; target_attitude_calculator_.is_enabled = 0; } diff --git a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.h b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.h index eee58276..ee05e19a 100644 --- a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.h +++ b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_calculator.h @@ -7,7 +7,7 @@ #include #include -#include "../../../../Library/quaternion.h" +#include /** * @enum APP_TARGET_ATT_CALC_MODE diff --git a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.c b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.c index 558fc6d1..42bd445a 100644 --- a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.c +++ b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.c @@ -6,14 +6,17 @@ #include #include -#include "../../../app_registry.h" +#include #include "target_attitude_from_orbit.h" -#include "../aocs_manager.h" -#include "../../../../Library/math_constants.h" -#include "../../../../Library/c2a_math.h" -#include "../../../../Library/vector3.h" -#include "../../../../Library/time_space.h" +#include +#include +#include +#include +#include + +// SatelliteParameters +#include static TargetAttitudeFromOrbit target_attitude_from_orbit_; const TargetAttitudeFromOrbit* const target_attitude_from_orbit = &target_attitude_from_orbit_; @@ -60,21 +63,15 @@ AppInfo APP_TAFO_create_app(void) static void APP_TAFO_init_(void) { - target_attitude_from_orbit_.main_target_direction = APP_TAFO_TARGET_DIRECITON_SUN; - target_attitude_from_orbit_.sub_target_direction = APP_TAFO_TARGET_DIRECITON_EARTH_CENTER; - target_attitude_from_orbit_.vec_to_main_target_body[0] = 1.0f; - target_attitude_from_orbit_.vec_to_main_target_body[1] = 0.0f; - target_attitude_from_orbit_.vec_to_main_target_body[2] = 0.0f; - target_attitude_from_orbit_.vec_to_sub_target_body[0] = 0.0f; - target_attitude_from_orbit_.vec_to_sub_target_body[1] = 1.0f; - target_attitude_from_orbit_.vec_to_sub_target_body[2] = 0.0f; - target_attitude_from_orbit_.offset_angle_axis = MATRIX33_ROTATION_AXIS_X; - target_attitude_from_orbit_.offset_angle_rad = 0.0f; - - // 東大正門 - target_attitude_from_orbit_.target_lla_rad_m[0] = PHYSICAL_CONST_degree_to_radian(35.7130f); - target_attitude_from_orbit_.target_lla_rad_m[1] = PHYSICAL_CONST_degree_to_radian(139.7596f); - target_attitude_from_orbit_.target_lla_rad_m[2] = 23.0f; + target_attitude_from_orbit_.main_target_direction = ATTITUDE_TARGET_PARAMETERS_main_target_direction; + target_attitude_from_orbit_.sub_target_direction = ATTITUDE_TARGET_PARAMETERS_sub_target_direction; + VECTOR3_copy(target_attitude_from_orbit_.vec_to_main_target_body, ATTITUDE_TARGET_PARAMETERS_vec_to_main_target_body); + VECTOR3_copy(target_attitude_from_orbit_.vec_to_sub_target_body, ATTITUDE_TARGET_PARAMETERS_vec_to_sub_target_body); + + target_attitude_from_orbit_.offset_angle_axis = ATTITUDE_TARGET_PARAMETERS_offset_angle_axis; + target_attitude_from_orbit_.offset_angle_rad = ATTITUDE_TARGET_PARAMETERS_offset_angle_rad; + + VECTOR3_copy(target_attitude_from_orbit_.target_lla_rad_m, ATTITUDE_TARGET_PARAMETERS_target_lla_rad_m); } diff --git a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.h b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.h index aa664cb8..ce21b374 100644 --- a/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.h +++ b/src/src_user/Applications/UserDefined/AOCS/TargetAttitude/target_attitude_from_orbit.h @@ -7,9 +7,9 @@ #include #include -#include "../../../../Library/physical_constants.h" -#include "../../../../Library/matrix33.h" -#include "../../../../Library/quaternion.h" +#include +#include +#include /** * @enum APP_TAFO_TARGET_DIRECITON diff --git a/src/src_user/Applications/UserDefined/AOCS/aocs_manager.c b/src/src_user/Applications/UserDefined/AOCS/aocs_manager.c index 0f91760b..50d15a30 100644 --- a/src/src_user/Applications/UserDefined/AOCS/aocs_manager.c +++ b/src/src_user/Applications/UserDefined/AOCS/aocs_manager.c @@ -7,18 +7,20 @@ #include "aocs_manager.h" #include #include -#include "../../../Library/c2a_math.h" -#include "../../../Library/math_constants.h" -#include "../../../Library/vector3.h" -#include "../../../Library/matrix33.h" -#include "../../../Library/ControlUtility/gyroscopic_effect.h" +#include +#include +#include +#include +#include #include "AttitudeControl/unloading.h" #include "aocs_mode_manager.h" // SatelliteParameters -#include "../../../Settings/SatelliteParameters/orbit_parameters.h" -#include "../../../Settings/SatelliteParameters/structure_parameters.h" +#include +#include +#include +#include static AocsManager aocs_manager_; const AocsManager* const aocs_manager = &aocs_manager_; @@ -46,29 +48,23 @@ static void APP_AOCS_MANAGER_init_(void) // 衛星特性 aocs_manager_.mass_sc_kg = STRUCTURE_PARAMETERS_mass_sc_kg; - VECTOR3_initialize(aocs_manager_.rmm_sc_body_Am2, 0.1f); - - aocs_manager_.inertia_tensor_sc_body_kgm2[0][0] = 0.1f; - aocs_manager_.inertia_tensor_sc_body_kgm2[0][1] = 0.0e-4f; - aocs_manager_.inertia_tensor_sc_body_kgm2[0][2] = 0.0e-4f; - aocs_manager_.inertia_tensor_sc_body_kgm2[1][0] = 0.0e-4f; - aocs_manager_.inertia_tensor_sc_body_kgm2[1][1] = 0.2f; - aocs_manager_.inertia_tensor_sc_body_kgm2[1][2] = 0.0e-4f; - aocs_manager_.inertia_tensor_sc_body_kgm2[2][0] = 0.0e-4f; - aocs_manager_.inertia_tensor_sc_body_kgm2[2][1] = 0.0e-4f; - aocs_manager_.inertia_tensor_sc_body_kgm2[2][2] = 0.2f; + VECTOR3_copy(aocs_manager_.rmm_sc_body_Am2, + STRUCTURE_PARAMETERS_rmm_sc_body_Am2); + MATRIX33_copy(aocs_manager_.inertia_tensor_sc_body_kgm2, + STRUCTURE_PARAMETERS_inertia_tensor_sc_body_kgm2); + // 角速度 VECTOR3_initialize(aocs_manager_.ang_vel_obs_body_rad_s, 0.0f); VECTOR3_initialize(aocs_manager_.ang_vel_est_body_rad_s, 0.0f); VECTOR3_initialize(aocs_manager_.ang_vel_target_body_rad_s, 0.0f); VECTOR3_initialize(aocs_manager_.ang_vel_error_body_rad_s, 0.0f); - aocs_manager_.limit_angular_velocity_rad_s = PHYSICAL_CONST_degree_to_radian(0.8f); + aocs_manager_.limit_angular_velocity_rad_s = ATTITUDE_CONTROL_PARAMETERS_limit_angular_velocity_rad_s; // Quaternion aocs_manager_.quaternion_obs_i2b = QUATERNION_make_unit(); aocs_manager_.quaternion_est_i2b = QUATERNION_make_unit(); - aocs_manager_.quaternion_target_i2t = QUATERNION_make_unit(); + aocs_manager_.quaternion_target_i2t = ATTITUDE_TARGET_PARAMETERS_quaternion_target_i2t; aocs_manager_.quaternion_error_b2t = QUATERNION_make_unit(); - aocs_manager_.limit_maneuver_angle_rad = PHYSICAL_CONST_degree_to_radian(30.0f); + aocs_manager_.limit_maneuver_angle_rad = ATTITUDE_CONTROL_PARAMETERS_limit_maneuver_angle_rad; // 太陽方向 const float kSqrtOneThird = 0.57735f; // ノルム1になる値 VECTOR3_initialize(aocs_manager_.sun_vec_obs_body, kSqrtOneThird); @@ -84,10 +80,10 @@ static void APP_AOCS_MANAGER_init_(void) VECTOR3_initialize(aocs_manager_.internal_torque_target_body_Nm, 0.0f); VECTOR3_initialize(aocs_manager_.external_torque_target_body_Nm, 0.0f); VECTOR3_initialize(aocs_manager_.torque_est_body_Nm, 0.0f); - VECTOR3_initialize(aocs_manager_.internal_torque_max_body_Nm, 5e-3f); // これで進めるが、必要になったら修正してよい - VECTOR3_initialize(aocs_manager_.external_torque_max_body_Nm, 3e-4f); // これで進めるが、必要になったら修正してよい - VECTOR3_initialize(aocs_manager_.constant_torque_body_Nm, 0.0f); - aocs_manager_.constant_torque_permission = AOCS_MANAGER_CONSTANT_TORQUE_DISABLE; + VECTOR3_copy(aocs_manager_.internal_torque_max_body_Nm, ATTITUDE_CONTROL_PARAMETERS_internal_torque_max_body_Nm); + VECTOR3_copy(aocs_manager_.external_torque_max_body_Nm, ATTITUDE_CONTROL_PARAMETERS_external_torque_max_body_Nm); + VECTOR3_copy(aocs_manager_.constant_torque_body_Nm, ATTITUDE_CONTROL_PARAMETERS_constant_torque_body_Nm); + aocs_manager_.constant_torque_permission = ATTITUDE_CONTROL_PARAMETERS_constant_torque_permission; // 磁気モーメント VECTOR3_initialize(aocs_manager_.mag_moment_target_body_Am2, 0.0f); // MTQ情報 diff --git a/src/src_user/Applications/UserDefined/AOCS/aocs_manager.h b/src/src_user/Applications/UserDefined/AOCS/aocs_manager.h index 6e1c1401..7bd99fc9 100644 --- a/src/src_user/Applications/UserDefined/AOCS/aocs_manager.h +++ b/src/src_user/Applications/UserDefined/AOCS/aocs_manager.h @@ -8,10 +8,10 @@ #include #include #include -#include "../../../Library/physical_constants.h" -#include "../../../Library/quaternion.h" -#include "../../DriverInstances/di_rw0003.h" -#include "../../DriverInstances/di_mtq_seiren.h" +#include +#include +#include +#include /** * @enum AOCS_MANAGER_ERROR diff --git a/src/src_user/Applications/UserDefined/AOCS/aocs_mode_manager.c b/src/src_user/Applications/UserDefined/AOCS/aocs_mode_manager.c index f18176d8..e364e211 100644 --- a/src/src_user/Applications/UserDefined/AOCS/aocs_mode_manager.c +++ b/src/src_user/Applications/UserDefined/AOCS/aocs_mode_manager.c @@ -13,10 +13,13 @@ #include #include #include -#include "./aocs_manager.h" -#include "../../../Library/vector3.h" -#include "../../../Library/physical_constants.h" -#include "../../../Library/math_constants.h" +#include "aocs_manager.h" +#include +#include +#include + +// SatelliteParameters +#include // #define APP_AOCS_MM_TEST_WITH_S2E //!< S2Eでテストするときにコメントを外すと実行後Bdotモードに遷移する #ifdef SILS_FW @@ -93,21 +96,21 @@ static void APP_AOCS_MM_init_(void) aocs_mode_manager_.bdot_retry_count = 0; aocs_mode_manager_.is_control_error_small = 0; - aocs_mode_manager_.ang_vel_conv_limit_rad_s = PHYSICAL_CONST_degree_to_radian(0.5f); - aocs_mode_manager_.ang_vel_conv_time_limit_s = 5.0f * 60.0f; + aocs_mode_manager_.ang_vel_conv_limit_rad_s = FDIR_PARAMETERS_ang_vel_conv_limit_rad_s; + aocs_mode_manager_.ang_vel_conv_time_limit_s = FDIR_PARAMETERS_ang_vel_conv_time_limit_s; - aocs_mode_manager_.ang_vel_norm_increase_limit_rad_s = PHYSICAL_CONST_degree_to_radian(0.5f); - aocs_mode_manager_.ang_vel_anomaly_detection_period_s = 200.0f; + aocs_mode_manager_.ang_vel_norm_increase_limit_rad_s = FDIR_PARAMETERS_ang_vel_norm_increase_limit_rad_s; + aocs_mode_manager_.ang_vel_anomaly_detection_period_s = FDIR_PARAMETERS_ang_vel_anomaly_detection_period_s; - aocs_mode_manager_.sun_angle_div_limit_rad = PHYSICAL_CONST_degree_to_radian(45.0f); - aocs_mode_manager_.sun_angle_div_time_limit_s = 50.0f * 60.0f; + aocs_mode_manager_.sun_angle_div_limit_rad = FDIR_PARAMETERS_sun_angle_div_limit_rad; + aocs_mode_manager_.sun_angle_div_time_limit_s = FDIR_PARAMETERS_sun_angle_div_time_limit_s; // Rough MTQを想定して初期値は大きめに設定、各モード遷移時に適切に設定することを想定 - aocs_mode_manager_.three_axis_div_limit_rad = PHYSICAL_CONST_degree_to_radian(30.0f); - aocs_mode_manager_.three_axis_div_time_limit_s = 5.0f * 60.0f; + aocs_mode_manager_.three_axis_div_limit_rad = FDIR_PARAMETERS_rough_three_axis_mtq_div_limit_rad; + aocs_mode_manager_.three_axis_div_time_limit_s = FDIR_PARAMETERS_rough_three_axis_mtq_div_time_limit_s; - aocs_mode_manager_.sun_invisible_time_limit_s = 50.0f * 60.0f; - aocs_mode_manager_.stt_invisible_time_limit_s = 10.0f * 60.0f; + aocs_mode_manager_.sun_invisible_time_limit_s = FDIR_PARAMETERS_sun_invisible_time_limit_s; + aocs_mode_manager_.stt_invisible_time_limit_s = FDIR_PARAMETERS_stt_invisible_time_limit_s; return; } diff --git a/src/src_user/Applications/UserDefined/AppStatus.c b/src/src_user/Applications/UserDefined/AppStatus.c index b588d1af..a7f0ee87 100644 --- a/src/src_user/Applications/UserDefined/AppStatus.c +++ b/src/src_user/Applications/UserDefined/AppStatus.c @@ -3,8 +3,8 @@ #include #include -#include "../../Library/vt100.h" -#include "../../TlmCmd/command_definitions.h" +#include +#include #include static ASInfo asi_; diff --git a/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.c b/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.c index b3c609ee..ed1df353 100644 --- a/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.c +++ b/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.c @@ -11,7 +11,7 @@ #include #include #include -#include "../../../Library/vector3.h" +#include #define APP_AOCS_DR_ALGORITHM_TLM_SIZE (104) //!< テレメトリ構造体サイズ(念のため実機で確認済み) diff --git a/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.h b/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.h index 5060b68c..63a97cee 100644 --- a/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.h +++ b/src/src_user/Applications/UserDefined/Cdh/aocs_data_recorder.h @@ -11,7 +11,7 @@ #include -#include "../AOCS/aocs_manager.h" +#include #include "non_volatile_memory_partition.h" diff --git a/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_manager.h b/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_manager.h index 49df1177..ea9d9c4b 100644 --- a/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_manager.h +++ b/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_manager.h @@ -9,7 +9,8 @@ #include // 下記は使うH/Wによって修正する -#include "../../DriverInstances/di_fm25v10.h" +#include + #define APP_NVM_MANAGER_STOP_ADDRESS (DI_FM25V10_STOP_GLOBAL_ADDRESS) //!< 不揮発メモリ管理アプリで扱う最大アドレス #define APP_NVM_MANAGER_MAX_LENGTH (DI_FM25V10_MAX_LENGTH) //!< 不揮発メモリ管理アプリで扱う最大アドレス diff --git a/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_parameter.h b/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_parameter.h index 3e194942..2a439b43 100644 --- a/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_parameter.h +++ b/src/src_user/Applications/UserDefined/Cdh/non_volatile_memory_parameter.h @@ -7,8 +7,8 @@ #include #include "non_volatile_memory_partition.h" -#include "../../../Settings/Applications/NvmParams/non_volatile_memory_normal_parameters.h" -#include "../../../Settings/Applications/NvmParams/non_volatile_memory_redundant_parameters.h" +#include +#include /** * @enum APP_NVM_PARAM_TYPE diff --git a/src/src_user/Applications/UserDefined/Power/power_switch_control.c b/src/src_user/Applications/UserDefined/Power/power_switch_control.c index 57a8ae4d..fe71f832 100644 --- a/src/src_user/Applications/UserDefined/Power/power_switch_control.c +++ b/src/src_user/Applications/UserDefined/Power/power_switch_control.c @@ -8,8 +8,8 @@ #include #include -#include "../../../IfWrapper/GPIO.h" -#include "../../../Settings/port_config.h" +#include +#include /** * @enum APP_PSC_OUTPUT_LOGIC diff --git a/src/src_user/Applications/UserDefined/Thermal/temperature_anomaly.c b/src/src_user/Applications/UserDefined/Thermal/temperature_anomaly.c index 2067ffa9..7bae4ba5 100644 --- a/src/src_user/Applications/UserDefined/Thermal/temperature_anomaly.c +++ b/src/src_user/Applications/UserDefined/Thermal/temperature_anomaly.c @@ -7,13 +7,13 @@ #include #include -#include "../../../Library/c2a_math.h" +#include #include "thermo_sensor.h" -#include "../../DriverInstances/di_mpu9250.h" -#include "../../DriverInstances/di_stim210.h" -#include "../../DriverInstances/di_sagitta.h" -#include "../../DriverInstances/di_rw0003.h" -#include "../../DriverInstances/di_oem7600.h" +#include +#include +#include +#include +#include static TemperatureAnomaly temperature_anomaly_; diff --git a/src/src_user/Applications/UserDefined/Thermal/thermo_sensor.c b/src/src_user/Applications/UserDefined/Thermal/thermo_sensor.c index 7cec95ae..3f57dc59 100644 --- a/src/src_user/Applications/UserDefined/Thermal/thermo_sensor.c +++ b/src/src_user/Applications/UserDefined/Thermal/thermo_sensor.c @@ -6,9 +6,9 @@ #include "thermo_sensor.h" #include -#include "../../../IfWrapper/ADC.h" -#include "../../../Settings/port_config.h" -#include "../../../Library/physical_constants.h" +#include +#include +#include static ThermoSensor thermo_sensor_; diff --git a/src/src_user/Applications/UserDefined/debug_apps.c b/src/src_user/Applications/UserDefined/debug_apps.c index ffb53791..5c67ac37 100644 --- a/src/src_user/Applications/UserDefined/debug_apps.c +++ b/src/src_user/Applications/UserDefined/debug_apps.c @@ -4,12 +4,12 @@ #include // for NULL #include -#include "../../Library/vt100.h" +#include #include #include #include #include -#include "../../TlmCmd/telemetry_definitions.h" +#include #include #include #include diff --git a/src/src_user/Applications/UserDefined/module_test_bench.c b/src/src_user/Applications/UserDefined/module_test_bench.c index d006dc0d..eef33a98 100644 --- a/src/src_user/Applications/UserDefined/module_test_bench.c +++ b/src/src_user/Applications/UserDefined/module_test_bench.c @@ -5,9 +5,9 @@ #include #include #include -#include "../../Library/c2a_math.h" -#include "../../Library/math_constants.h" -#include "../../Library/physical_constants.h" +#include +#include +#include #include "AOCS/aocs_manager.h" // #define RUN_EXAMPLE //!< Enable test of the test bench diff --git a/src/src_user/Drivers/Aocs/mpu9250.c b/src/src_user/Drivers/Aocs/mpu9250.c index c1ce68a1..047c93b4 100644 --- a/src/src_user/Drivers/Aocs/mpu9250.c +++ b/src/src_user/Drivers/Aocs/mpu9250.c @@ -4,11 +4,11 @@ * @brief MPU9250のDriver */ -#include "./mpu9250.h" +#include "mpu9250.h" #include -#include "../../Library/physical_constants.h" -#include "../../Library/vector3.h" -#include "../../Library/matrix33.h" +#include +#include +#include #define MPU9250_STREAM_TLM_CMD (0) //!< テレコマで使うストリーム #define MPU9250_TX_FOR_REC_FRAME_SIZE (1) //!< 観測時の1回の送信データ長(バイト) diff --git a/src/src_user/Drivers/Aocs/mpu9250.h b/src/src_user/Drivers/Aocs/mpu9250.h index 885a4117..daf14a44 100644 --- a/src/src_user/Drivers/Aocs/mpu9250.h +++ b/src/src_user/Drivers/Aocs/mpu9250.h @@ -8,8 +8,8 @@ #include #include -#include "../../Library/quaternion.h" -#include "../../Library/physical_constants.h" +#include +#include /** * @enum MPU9250_ANG_VEL_RANGE diff --git a/src/src_user/Drivers/Aocs/mtq_seiren.c b/src/src_user/Drivers/Aocs/mtq_seiren.c index 175286eb..32a7df10 100644 --- a/src/src_user/Drivers/Aocs/mtq_seiren.c +++ b/src/src_user/Drivers/Aocs/mtq_seiren.c @@ -4,10 +4,10 @@ * @brief MTQ_SEIRENのDriver */ -#include "./mtq_seiren.h" +#include "mtq_seiren.h" #include -#include "../../Library/vector3.h" +#include static uint32_t MTQ_SEIREN_pwm_period_ms_ = 1000; // TODO_L: 今はコマンドで自由に変更が効くようになっているが、const化するかどうか検討が必要 diff --git a/src/src_user/Drivers/Aocs/mtq_seiren.h b/src/src_user/Drivers/Aocs/mtq_seiren.h index ab1f295b..31af36ef 100644 --- a/src/src_user/Drivers/Aocs/mtq_seiren.h +++ b/src/src_user/Drivers/Aocs/mtq_seiren.h @@ -8,9 +8,9 @@ #include #include -#include "../../IfWrapper/GPIO.h" -#include "../../Library/physical_constants.h" -#include "../../Library/c2a_math.h" +#include +#include +#include /** * @struct MTQ_SEIREN_POLARITY diff --git a/src/src_user/Drivers/Aocs/nanossoc_d60.c b/src/src_user/Drivers/Aocs/nanossoc_d60.c index f7e2c2fb..0fa3d07e 100644 --- a/src/src_user/Drivers/Aocs/nanossoc_d60.c +++ b/src/src_user/Drivers/Aocs/nanossoc_d60.c @@ -4,8 +4,8 @@ * @brief nanoSSOC_D60のDriver */ -#include "./nanossoc_d60.h" -#include "../../Library/vector3.h" +#include "nanossoc_d60.h" +#include #include // for memcpy #include diff --git a/src/src_user/Drivers/Aocs/nanossoc_d60.h b/src/src_user/Drivers/Aocs/nanossoc_d60.h index 04844ccc..9986fd89 100644 --- a/src/src_user/Drivers/Aocs/nanossoc_d60.h +++ b/src/src_user/Drivers/Aocs/nanossoc_d60.h @@ -8,8 +8,8 @@ #include #include -#include "../../Library/quaternion.h" -#include "../../Library/physical_constants.h" +#include +#include /** * @enum NANOSSOC_D60_ErrorCode diff --git a/src/src_user/Drivers/Aocs/oem7600.c b/src/src_user/Drivers/Aocs/oem7600.c index ee60e183..2779fec0 100644 --- a/src/src_user/Drivers/Aocs/oem7600.c +++ b/src/src_user/Drivers/Aocs/oem7600.c @@ -4,8 +4,8 @@ * @brief OEM7600のDriver */ -#include "./oem7600.h" -#include "../../Library/physical_constants.h" +#include "oem7600.h" +#include #include // for memcpy #include // for snprintf diff --git a/src/src_user/Drivers/Aocs/oem7600.h b/src/src_user/Drivers/Aocs/oem7600.h index 49d6f574..d2fa4ced 100644 --- a/src/src_user/Drivers/Aocs/oem7600.h +++ b/src/src_user/Drivers/Aocs/oem7600.h @@ -7,7 +7,7 @@ #define OEM7600_H_ #include -#include "../../IfWrapper/GPIO.h" +#include #include #include diff --git a/src/src_user/Drivers/Aocs/rm3100.c b/src/src_user/Drivers/Aocs/rm3100.c index 351e30ec..1cbbf4bb 100644 --- a/src/src_user/Drivers/Aocs/rm3100.c +++ b/src/src_user/Drivers/Aocs/rm3100.c @@ -4,10 +4,10 @@ * @brief RM3100のDriver */ -#include "./rm3100.h" -#include "../../Library/matrix33.h" -#include "../../Library/vector3.h" -#include "../../Library/c2a_math.h" +#include "rm3100.h" +#include +#include +#include #define RM3100_STREAM_TLM_CMD (0) #define RM3100_RX_FRAME_SIZE (9) //!< RM3100の場合この値で固定 diff --git a/src/src_user/Drivers/Aocs/rm3100.h b/src/src_user/Drivers/Aocs/rm3100.h index 4c049324..c037caa3 100644 --- a/src/src_user/Drivers/Aocs/rm3100.h +++ b/src/src_user/Drivers/Aocs/rm3100.h @@ -8,8 +8,8 @@ #include #include -#include "../../Library/quaternion.h" -#include "../../Library/physical_constants.h" +#include +#include extern const uint8_t RM3100_kCmmMode; //!< Continuous Measure Modeに入れるための設定値 diff --git a/src/src_user/Drivers/Aocs/rw0003.c b/src/src_user/Drivers/Aocs/rw0003.c index 323038c8..e5b59bc8 100644 --- a/src/src_user/Drivers/Aocs/rw0003.c +++ b/src/src_user/Drivers/Aocs/rw0003.c @@ -8,13 +8,13 @@ #include #endif -#include "./rw0003.h" +#include "rw0003.h" #include #include #include -#include "../../Library/vector3.h" -#include "../../Library/c2a_math.h" +#include +#include // #define DRIVER_RW0003_DEBUG_SHOW_REC_DATA diff --git a/src/src_user/Drivers/Aocs/rw0003.h b/src/src_user/Drivers/Aocs/rw0003.h index a90b0db8..bfdcfc08 100644 --- a/src/src_user/Drivers/Aocs/rw0003.h +++ b/src/src_user/Drivers/Aocs/rw0003.h @@ -8,8 +8,8 @@ #include #include -#include "../../Library/physical_constants.h" -#include "../../Library/c2a_math.h" +#include +#include extern const float RW0003_kMaxTorqueNm; //!< 出力可能最大トルク [Nm] extern const float RW0003_kMomentOfInertiaKgm2; //!< ホイール慣性モーメント [kgm2] diff --git a/src/src_user/Drivers/Aocs/sagitta.c b/src/src_user/Drivers/Aocs/sagitta.c index b6a72dd3..2cb79bf4 100644 --- a/src/src_user/Drivers/Aocs/sagitta.c +++ b/src/src_user/Drivers/Aocs/sagitta.c @@ -3,14 +3,14 @@ * @file sagitta.c * @brief SAGITTAのDriver */ -#include "./sagitta.h" +#include "sagitta.h" #include #include // for memcpy #include -#include "../../Library/xxhash.h" -#include "../../Library/physical_constants.h" +#include +#include // #define DRIVER_SAGITTA_DEBUG_SHOW_REC_DATA diff --git a/src/src_user/Drivers/Aocs/sagitta.h b/src/src_user/Drivers/Aocs/sagitta.h index e363682b..9e3e0dc3 100644 --- a/src/src_user/Drivers/Aocs/sagitta.h +++ b/src/src_user/Drivers/Aocs/sagitta.h @@ -7,8 +7,8 @@ #include #include -#include "../../Library/physical_constants.h" -#include "../../Library/quaternion.h" +#include +#include #define SAGITTA_PARAMETER_LOG_LEVEL_LENGTH (16) #define SAGITTA_PARAMETER_LIMITS_LENGTH (10) diff --git a/src/src_user/Drivers/Aocs/stim210.c b/src/src_user/Drivers/Aocs/stim210.c index 8b10608f..bb72b613 100644 --- a/src/src_user/Drivers/Aocs/stim210.c +++ b/src/src_user/Drivers/Aocs/stim210.c @@ -4,13 +4,13 @@ * @brief STIM210のDriver */ -#include "./stim210.h" +#include "stim210.h" #include #include #include -#include "../../Library/vector3.h" -#include "../../Library/matrix33.h" -#include "../../Library/crc8.h" +#include +#include +#include #define STIM210_STREAM_TLM_CMD (0) //!< テレコマで使うストリーム diff --git a/src/src_user/Drivers/Aocs/stim210.h b/src/src_user/Drivers/Aocs/stim210.h index 06234661..9ab1fbcd 100644 --- a/src/src_user/Drivers/Aocs/stim210.h +++ b/src/src_user/Drivers/Aocs/stim210.h @@ -9,9 +9,9 @@ #include #include -#include "../../IfWrapper/GPIO.h" -#include "../../Library/physical_constants.h" -#include "../../Library/quaternion.h" +#include +#include +#include /** * @enum STIM210_OPERATION_MODE diff --git a/src/src_user/Drivers/Cdh/fm25v10.c b/src/src_user/Drivers/Cdh/fm25v10.c index 0af66a33..8cbd6492 100644 --- a/src/src_user/Drivers/Cdh/fm25v10.c +++ b/src/src_user/Drivers/Cdh/fm25v10.c @@ -4,7 +4,7 @@ */ #pragma section REPRO -#include "./fm25v10.h" +#include "fm25v10.h" #include #include diff --git a/src/src_user/Drivers/Etc/mobc.c b/src/src_user/Drivers/Etc/mobc.c index d9e4ccf4..23ebf38f 100644 --- a/src/src_user/Drivers/Etc/mobc.c +++ b/src/src_user/Drivers/Etc/mobc.c @@ -6,7 +6,7 @@ // TODO_L: DS側のTCPが整理されたら,TCP関連を撲滅し,CTCPに統一する -#include "./mobc.h" +#include "mobc.h" #include #include #include diff --git a/src/src_user/Drivers/Power/ina260.c b/src/src_user/Drivers/Power/ina260.c index 1057f284..8662f05c 100644 --- a/src/src_user/Drivers/Power/ina260.c +++ b/src/src_user/Drivers/Power/ina260.c @@ -4,7 +4,7 @@ * @brief INA260のDriver */ -#include "./ina260.h" +#include "ina260.h" #include #include diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.cpp b/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.cpp index e8243a14..106ecd86 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.cpp +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.cpp @@ -4,7 +4,7 @@ */ #include "./ADC_CHIPKIT.h" -#include "../../../Settings/port_config.h" +#include #include int ADC_CHIPKIT_initialize(unsigned int init_param) diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.h b/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.h index efd7f640..c3a75224 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.h +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/ADC_CHIPKIT.h @@ -1,7 +1,7 @@ #ifndef ADC_CHIPKIT_H_ #define ADC_CHIPKIT_H_ -#include "../../ADC.h" +#include #ifdef __cplusplus extern "C" { diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.cpp b/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.cpp index 049e45e1..799c5e64 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.cpp +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.cpp @@ -1,6 +1,6 @@ #include "./GPIO_CHIPKIT.h" -#include "../../../Settings/port_config.h" +#include #include diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.h b/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.h index ace079e9..664a3442 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.h +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/GPIO_CHIPKIT.h @@ -1,7 +1,7 @@ #ifndef GPIO_CHIPKIT_H_ #define GPIO_CHIPKIT_H_ -#include "../../GPIO.h" +#include #ifdef __cplusplus extern "C" { diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/I2C_CHIPKIT.cpp b/src/src_user/IfWrapper/Arduino/CHIPKIT/I2C_CHIPKIT.cpp index fae0dac0..a2c44a87 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/I2C_CHIPKIT.cpp +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/I2C_CHIPKIT.cpp @@ -4,7 +4,7 @@ */ #include "./I2C_CHIPKIT.h" -#include "../../../Settings/port_config.h" +#include extern "C" { #include diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/UART_CHIPKIT.cpp b/src/src_user/IfWrapper/Arduino/CHIPKIT/UART_CHIPKIT.cpp index 027c37d5..601ff146 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/UART_CHIPKIT.cpp +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/UART_CHIPKIT.cpp @@ -2,7 +2,7 @@ // Arduino(C++)のSerialポートををCで使えるようにするためのラッパ関数 #include "./UART_CHIPKIT.h" -#include "../../../Settings/port_config.h" +#include #include diff --git a/src/src_user/IfWrapper/Arduino/CHIPKIT/spi_chipkit.cpp b/src/src_user/IfWrapper/Arduino/CHIPKIT/spi_chipkit.cpp index c438dd8e..8fb26332 100644 --- a/src/src_user/IfWrapper/Arduino/CHIPKIT/spi_chipkit.cpp +++ b/src/src_user/IfWrapper/Arduino/CHIPKIT/spi_chipkit.cpp @@ -5,12 +5,12 @@ */ #include "./spi_chipkit.h" -#include "../../../Settings/port_config.h" +#include extern "C" { #include -#include "../../GPIO.h" +#include } #include diff --git a/src/src_user/IfWrapper/Arduino/UART_ARDUINO.c b/src/src_user/IfWrapper/Arduino/UART_ARDUINO.c index 2406a77a..7d0cc240 100644 --- a/src/src_user/IfWrapper/Arduino/UART_ARDUINO.c +++ b/src/src_user/IfWrapper/Arduino/UART_ARDUINO.c @@ -1,6 +1,6 @@ #include "./CHIPKIT/UART_CHIPKIT.h" -#include "../../Settings/port_config.h" +#include int UART_init(void* my_uart_v) { diff --git a/src/src_user/Library/ControlUtility/cross_product_control.c b/src/src_user/Library/ControlUtility/cross_product_control.c index d5d5d7eb..8c9b48d1 100644 --- a/src/src_user/Library/ControlUtility/cross_product_control.c +++ b/src/src_user/Library/ControlUtility/cross_product_control.c @@ -8,8 +8,8 @@ #include -#include "../vector3.h" -#include "../math_constants.h" +#include +#include void CROSS_PRODUCT_CONTROL_init(CrossProductControl* cross_product_control) diff --git a/src/src_user/Library/ControlUtility/cross_product_control.h b/src/src_user/Library/ControlUtility/cross_product_control.h index 068246dd..454897c1 100644 --- a/src/src_user/Library/ControlUtility/cross_product_control.h +++ b/src/src_user/Library/ControlUtility/cross_product_control.h @@ -5,8 +5,8 @@ #ifndef CROSS_PRODUCT_CONTROL_H_ #define CROSS_PRODUCT_CONTROL_H_ -#include "../physical_constants.h" -#include "../c2a_math.h" +#include +#include /** * @enum CROSS_PRODUCT_CONTROL_ERROR diff --git a/src/src_user/Library/ControlUtility/gyroscopic_effect.c b/src/src_user/Library/ControlUtility/gyroscopic_effect.c index 5cb24517..32d78f87 100644 --- a/src/src_user/Library/ControlUtility/gyroscopic_effect.c +++ b/src/src_user/Library/ControlUtility/gyroscopic_effect.c @@ -6,8 +6,8 @@ #include "gyroscopic_effect.h" -#include "../vector3.h" -#include "../matrix33.h" +#include +#include void GYROSCOPIC_EFFECT_calculate_gyroscopic_torque(float gyroscopic_trq_Nm[PHYSICAL_CONST_THREE_DIM], diff --git a/src/src_user/Library/ControlUtility/gyroscopic_effect.h b/src/src_user/Library/ControlUtility/gyroscopic_effect.h index 88141064..293f7246 100644 --- a/src/src_user/Library/ControlUtility/gyroscopic_effect.h +++ b/src/src_user/Library/ControlUtility/gyroscopic_effect.h @@ -6,7 +6,7 @@ #ifndef GYROSCOPIC_EFFECT_H_ #define GYROSCOPIC_EFFECT_H_ -#include "../physical_constants.h" +#include /** diff --git a/src/src_user/Library/Orbit/kepler_orbit.c b/src/src_user/Library/Orbit/kepler_orbit.c index 075b8eb2..4b9631b7 100644 --- a/src/src_user/Library/Orbit/kepler_orbit.c +++ b/src/src_user/Library/Orbit/kepler_orbit.c @@ -7,9 +7,9 @@ #include "kepler_orbit.h" #include -#include "../matrix33.h" -#include "../vector3.h" -#include "../math_constants.h" +#include +#include +#include #include #define KEPLER_ORBIT_ECCENTRICITY_THRESHOLD (1.0e-5f) //!< 円軌道とみなす離心率閾値 diff --git a/src/src_user/Library/Orbit/kepler_orbit.h b/src/src_user/Library/Orbit/kepler_orbit.h index a2fac0eb..0ccd7df7 100644 --- a/src/src_user/Library/Orbit/kepler_orbit.h +++ b/src/src_user/Library/Orbit/kepler_orbit.h @@ -5,8 +5,8 @@ #ifndef KEPLER_ORBIT_H_ #define KEPLER_ORBIT_H_ -#include "../physical_constants.h" -#include "../c2a_math.h" +#include +#include /** * @struct KeplerOrbitalElements diff --git a/src/src_user/Library/Orbit/sgp4.c b/src/src_user/Library/Orbit/sgp4.c index d2de1c4f..f1145d59 100644 --- a/src/src_user/Library/Orbit/sgp4.c +++ b/src/src_user/Library/Orbit/sgp4.c @@ -9,10 +9,10 @@ #include "sgp4.h" #include -#include "../physical_constants.h" -#include "../math_constants.h" -#include "../matrix33.h" -#include "../vector3.h" +#include +#include +#include +#include #include // SGP4内での使う定数 diff --git a/src/src_user/Library/Orbit/sgp4.h b/src/src_user/Library/Orbit/sgp4.h index 036da371..94f63e77 100644 --- a/src/src_user/Library/Orbit/sgp4.h +++ b/src/src_user/Library/Orbit/sgp4.h @@ -8,8 +8,8 @@ #define SGP4_H_ #include -#include "../physical_constants.h" -#include "../c2a_math.h" +#include +#include #define SGP4_NUM_COEFF_C (5) //!< C係数の要素数 #define SGP4_NUM_COEFF_D (4) //!< D係数の要素数 diff --git a/src/src_user/Library/SignalProcess/spike_filter.h b/src/src_user/Library/SignalProcess/spike_filter.h index 9106b0c8..65929be8 100644 --- a/src/src_user/Library/SignalProcess/spike_filter.h +++ b/src/src_user/Library/SignalProcess/spike_filter.h @@ -7,8 +7,8 @@ #define SPIKE_FILTER_H_ #include -#include "../c2a_math.h" -#include "../physical_constants.h" +#include +#include /** * @struct SpikeFilter_Config diff --git a/src/src_user/Library/SignalProcess/z_filter.c b/src/src_user/Library/SignalProcess/z_filter.c index e1fe0a7f..8abc7bf3 100644 --- a/src/src_user/Library/SignalProcess/z_filter.c +++ b/src/src_user/Library/SignalProcess/z_filter.c @@ -7,7 +7,7 @@ #include "z_filter.h" #include -#include "../math_constants.h" +#include //!< bilinear transformation diff --git a/src/src_user/Library/SignalProcess/z_filter.h b/src/src_user/Library/SignalProcess/z_filter.h index b7152c3b..45f9362d 100644 --- a/src/src_user/Library/SignalProcess/z_filter.h +++ b/src/src_user/Library/SignalProcess/z_filter.h @@ -7,7 +7,7 @@ #define Z_FILTER_H_ #include -#include "../c2a_math.h" +#include #define Z_FILTER_ORDER_MAX 2 //!< 離散フィルタ最高次数 diff --git a/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_normal_parameters.c b/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_normal_parameters.c index f63397ee..c44af906 100644 --- a/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_normal_parameters.c +++ b/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_normal_parameters.c @@ -6,7 +6,7 @@ * https://docs.google.com/spreadsheets/d/1JWxLqdwr3IzQBAkYI4zkRBb0jKZwCUtGaSDt9z3XXPQ/edit#gid=1413802869 */ #include "non_volatile_memory_normal_parameters.h" -#include "../../../Applications/UserDefined/Cdh/non_volatile_memory_parameter.h" +#include void NVM_NORMAL_PARAMS_register(void) { diff --git a/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_redundant_parameters.c b/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_redundant_parameters.c index b274404f..f7554e3d 100644 --- a/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_redundant_parameters.c +++ b/src/src_user/Settings/Applications/NvmParams/non_volatile_memory_redundant_parameters.c @@ -6,7 +6,7 @@ * https://docs.google.com/spreadsheets/d/1JWxLqdwr3IzQBAkYI4zkRBb0jKZwCUtGaSDt9z3XXPQ/edit#gid=1180200168 */ #include "non_volatile_memory_redundant_parameters.h" -#include "../../../Applications/UserDefined/Cdh/non_volatile_memory_parameter.h" +#include void NVM_REDUNDANT_PARAMS_register(void) { diff --git a/src/src_user/Settings/CMakeLists.txt b/src/src_user/Settings/CMakeLists.txt index cea67b56..d3fab7b8 100644 --- a/src/src_user/Settings/CMakeLists.txt +++ b/src/src_user/Settings/CMakeLists.txt @@ -48,6 +48,20 @@ set(C2A_SRCS # Satellite Parameters ${C2A_SATELLITE_PARAMETERS_DIR}/orbit_parameters.c ${C2A_SATELLITE_PARAMETERS_DIR}/structure_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/attitude_target_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/attitude_determination_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/attitude_control_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/fdir_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/ina260_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/mpu9250_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/rm3100_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/nanossoc_d60_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/oem7600_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/stim210_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/sagitta_parameters.c + # ${C2A_SATELLITE_PARAMETERS_DIR}/seiren_mtq_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/rw0003_parameters.c + ${C2A_SATELLITE_PARAMETERS_DIR}/component_selector_parameters.c ) add_library(${PROJECT_NAME} OBJECT ${C2A_SRCS}) diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_basic_sensor_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_basic_sensor_update.c index 7c6f4f56..ddea0cda 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_basic_sensor_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_basic_sensor_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_basic_sensor_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_cdh_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_cdh_update.c index f04e2316..f2423290 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_cdh_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_cdh_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_cdh_update.h" -#include "../../../../TlmCmd/block_command_definitions.h" -#include "../../../../Applications/app_registry.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_debug_display.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_debug_display.c index bc9cdef3..55229adc 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_debug_display.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_debug_display.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_debug_display.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_drivers_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_drivers_update.c index 13f7051e..42700ca5 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_drivers_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_drivers_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_drivers_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_gs_related_process.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_gs_related_process.c index 36e9de5d..39b78267 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_gs_related_process.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_gs_related_process.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_gs_related_process.h" -#include "../../../../TlmCmd/block_command_definitions.h" -#include "../../../../Applications/app_registry.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_inertial_ref_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_inertial_ref_update.c index 0a7bd884..36934bab 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_inertial_ref_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_inertial_ref_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_inertial_ref_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_mtq_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_mtq_update.c index 7296c720..553aacb6 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_mtq_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_mtq_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_mtq_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_oem7600_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_oem7600_update.c index b3c809ae..0d64c648 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_oem7600_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_oem7600_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_oem7600_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rm3100_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rm3100_update.c index cbaf44f8..dd929aa0 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rm3100_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rm3100_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_rm3100_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rw_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rw_update.c index a7f0c5d7..95d09712 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rw_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_rw_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_rw_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stim210_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stim210_update.c index 92646deb..3a836acb 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stim210_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stim210_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_stim210_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stt_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stt_update.c index 27a2229d..80b4b542 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stt_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_stt_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_stt_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_sun_vector_update.c b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_sun_vector_update.c index ce2531a7..0d878c9e 100644 --- a/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_sun_vector_update.c +++ b/src/src_user/Settings/Modes/TaskLists/Elements/tl_elem_sun_vector_update.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_elem_sun_vector_update.h" -#include "../../../../Applications/app_registry.h" -#include "../../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_bdot.c b/src/src_user/Settings/Modes/TaskLists/tl_bdot.c index ee5bf9ac..2c95c9df 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_bdot.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_bdot.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_bdot.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_fine_three_axis.c b/src/src_user/Settings/Modes/TaskLists/tl_fine_three_axis.c index 0a684235..1fdf6ee7 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_fine_three_axis.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_fine_three_axis.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_fine_three_axis.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_gpsr_range_observe.c b/src/src_user/Settings/Modes/TaskLists/tl_gpsr_range_observe.c index 770a1f45..5e1fe596 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_gpsr_range_observe.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_gpsr_range_observe.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_gpsr_range_observe.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_initial.c b/src/src_user/Settings/Modes/TaskLists/tl_initial.c index acab48ae..2431b536 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_initial.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_initial.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_initial.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_rough_sun_pointing.c b/src/src_user/Settings/Modes/TaskLists/tl_rough_sun_pointing.c index 3905b595..b43e1848 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_rough_sun_pointing.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_rough_sun_pointing.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_rough_sun_pointing.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis.c b/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis.c index e15d253a..9e933045 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_rough_three_axis.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis_rw.c b/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis_rw.c index aec12a3d..8c455a3d 100644 --- a/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis_rw.c +++ b/src/src_user/Settings/Modes/TaskLists/tl_rough_three_axis_rw.c @@ -5,8 +5,8 @@ #pragma section REPRO #include "tl_rough_three_axis_rw.h" -#include "../../../Applications/app_registry.h" -#include "../../../TlmCmd/block_command_definitions.h" +#include +#include #include diff --git a/src/src_user/Settings/Modes/Transitions/sl_bdot.c b/src/src_user/Settings/Modes/Transitions/sl_bdot.c index 09cb1483..074e1b46 100644 --- a/src/src_user/Settings/Modes/Transitions/sl_bdot.c +++ b/src/src_user/Settings/Modes/Transitions/sl_bdot.c @@ -6,16 +6,20 @@ #pragma section REPRO #include "sl_bdot.h" -#include "../../../TlmCmd/block_command_definitions.h" -#include "../../../TlmCmd/command_definitions.h" -#include "../../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../../Applications/DriverInstances/di_rm3100.h" -#include "../../../Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.h" +#include +#include +#include +#include +#include #include #include #include +// Satellite Parameters +#include +#include + void BCL_load_initial_to_bdot(void) { cycle_t bc_cycle = OBCT_sec2cycle(1); @@ -97,15 +101,15 @@ void BCL_load_any_to_bdot(void) BCL_tool_register_cmd(OBCT_sec2cycle(time_sec), Cmd_CODE_DI_RM3100_SET_MAG_BIAS_COMPO_NT); time_sec += 1; - // 使う磁気センサをExternalに設定 - BCL_tool_prepare_param_uint8(APP_MAG_SELECTOR_STATE_RM_EXT); + // 使う磁気センサを設定 + BCL_tool_prepare_param_uint8(COMPONENT_SELECTOR_PARAMETERS_initial_selected_magnetometer); BCL_tool_register_cmd(OBCT_sec2cycle(time_sec), Cmd_CODE_APP_MAG_SELECTOR_SET_STATE); time_sec += 1; BCL_tool_register_cmd(OBCT_sec2cycle(time_sec), Cmd_CODE_MM_FINISH_TRANSITION); // 自動モード遷移ON - time_sec += 5 * 60; + time_sec += FDIR_PARAMETERS_bdot_start_mode_manager_time_s; BCL_tool_prepare_param_uint8(1); BCL_tool_register_cmd(OBCT_sec2cycle(time_sec), Cmd_CODE_APP_AOCS_MM_SET_AUTO_MODE_TRANSITION); diff --git a/src/src_user/Settings/Modes/Transitions/sl_fine_three_axis.c b/src/src_user/Settings/Modes/Transitions/sl_fine_three_axis.c index f3c3816c..dd7f1ab7 100644 --- a/src/src_user/Settings/Modes/Transitions/sl_fine_three_axis.c +++ b/src/src_user/Settings/Modes/Transitions/sl_fine_three_axis.c @@ -6,15 +6,18 @@ #pragma section REPRO #include "sl_fine_three_axis.h" -#include "../../../TlmCmd/block_command_definitions.h" -#include "../../../TlmCmd/command_definitions.h" -#include "../../../Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gyro_selector.h" -#include "../../../Library/physical_constants.h" +#include +#include +#include +#include #include #include #include +// Satellite Parameters +#include + void BCL_load_rough_three_axis_rw_to_fine_three_axis(void) { uint32_t timing_sec = 1; @@ -24,8 +27,8 @@ void BCL_load_rough_three_axis_rw_to_fine_three_axis(void) timing_sec++; // 自動モード遷移閾値変更 - BCL_tool_prepare_param_float(PHYSICAL_CONST_degree_to_radian(5.0f)); - BCL_tool_prepare_param_float(1.0f * 60.0f); + BCL_tool_prepare_param_float(FDIR_PARAMETERS_fine_three_axis_div_limit_rad); + BCL_tool_prepare_param_float(FDIR_PARAMETERS_fine_three_axis_div_time_limit_s); BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_APP_AOCS_MM_SET_THREE_AXIS_THRESHOLD); timing_sec++; @@ -46,7 +49,7 @@ void BCL_load_rough_three_axis_rw_to_fine_three_axis(void) BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_MM_FINISH_TRANSITION); // 自動モード遷移ON - timing_sec += (5 * 60); + timing_sec += FDIR_PARAMETERS_fine_three_axis_start_mode_manager_time_s; BCL_tool_prepare_param_uint8(1); BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_APP_AOCS_MM_SET_AUTO_MODE_TRANSITION); } diff --git a/src/src_user/Settings/Modes/Transitions/sl_initial.c b/src/src_user/Settings/Modes/Transitions/sl_initial.c index ad5b50fd..50fbe362 100644 --- a/src/src_user/Settings/Modes/Transitions/sl_initial.c +++ b/src/src_user/Settings/Modes/Transitions/sl_initial.c @@ -5,10 +5,10 @@ #pragma section REPRO #include "sl_initial.h" -#include "../../../TlmCmd/block_command_definitions.h" -#include "../../../TlmCmd/command_definitions.h" -#include "../../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../../Applications/DriverInstances/di_ina260.h" +#include +#include +#include +#include #include #include diff --git a/src/src_user/Settings/Modes/Transitions/sl_rough_sun_pointing.c b/src/src_user/Settings/Modes/Transitions/sl_rough_sun_pointing.c index 2c2dc083..70963450 100644 --- a/src/src_user/Settings/Modes/Transitions/sl_rough_sun_pointing.c +++ b/src/src_user/Settings/Modes/Transitions/sl_rough_sun_pointing.c @@ -6,14 +6,17 @@ #pragma section REPRO #include "sl_rough_sun_pointing.h" -#include "../../../TlmCmd/block_command_definitions.h" -#include "../../../TlmCmd/command_definitions.h" -#include "../../../Applications/UserDefined/Power/power_switch_control.h" +#include +#include +#include #include #include #include +// Satellite Parameters +#include + void BCL_load_bdot_to_rough_sun_pointing(void) { cycle_t bc_cycle = OBCT_sec2cycle(1); @@ -31,7 +34,7 @@ void BCL_load_bdot_to_rough_sun_pointing(void) BCL_tool_register_cmd(bc_cycle, Cmd_CODE_MM_FINISH_TRANSITION); // 自動モード遷移ON - bc_cycle += OBCT_sec2cycle(25 * 60); + bc_cycle += OBCT_sec2cycle(FDIR_PARAMETERS_sun_pointing_start_mode_manager_time_s); BCL_tool_prepare_param_uint8(1); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_APP_AOCS_MM_SET_AUTO_MODE_TRANSITION); } diff --git a/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis.c b/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis.c index d71d2ffc..dcd9030e 100644 --- a/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis.c +++ b/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis.c @@ -6,13 +6,15 @@ #pragma section REPRO #include "sl_rough_three_axis.h" -#include "../../../TlmCmd/block_command_definitions.h" -#include "../../../TlmCmd/command_definitions.h" -#include "../../../Library/physical_constants.h" +#include +#include +#include #include #include +// Satellite Parameters +#include void BCL_load_rough_sun_pointing_to_rough_three_axis(void) { @@ -23,8 +25,8 @@ void BCL_load_rough_sun_pointing_to_rough_three_axis(void) // 自動モード遷移閾値変更 timing_sec++; - BCL_tool_prepare_param_float(PHYSICAL_CONST_degree_to_radian(30.0f)); - BCL_tool_prepare_param_float(5.0f * 60.0f); + BCL_tool_prepare_param_float(FDIR_PARAMETERS_rough_three_axis_mtq_div_limit_rad); + BCL_tool_prepare_param_float(FDIR_PARAMETERS_rough_three_axis_mtq_div_time_limit_s); BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_APP_AOCS_MM_SET_THREE_AXIS_THRESHOLD); // モード遷移完了 @@ -32,7 +34,7 @@ void BCL_load_rough_sun_pointing_to_rough_three_axis(void) BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_MM_FINISH_TRANSITION); // 自動モード遷移ON - timing_sec += (35 * 60); + timing_sec += FDIR_PARAMETERS_rough_three_axis_mtq_start_mode_manager_time_s; BCL_tool_prepare_param_uint8(1); BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_APP_AOCS_MM_SET_AUTO_MODE_TRANSITION); } diff --git a/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis_rw.c b/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis_rw.c index d9b70357..4f8582b0 100644 --- a/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis_rw.c +++ b/src/src_user/Settings/Modes/Transitions/sl_rough_three_axis_rw.c @@ -6,16 +6,19 @@ #pragma section REPRO #include "sl_rough_three_axis_rw.h" -#include "../../../TlmCmd/block_command_definitions.h" -#include "../../../TlmCmd/command_definitions.h" -#include "../../../Applications/UserDefined/AOCS/aocs_manager.h" -#include "../../../Library/physical_constants.h" -#include "../../../Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.h" +#include +#include +#include +#include +#include #include #include #include +// Satellite Parameters +#include + void BCL_load_rough_three_axis_to_rough_three_axis_rw(void) { uint32_t timing_sec = 1; @@ -25,8 +28,8 @@ void BCL_load_rough_three_axis_to_rough_three_axis_rw(void) // 自動モード遷移閾値変更 timing_sec++; - BCL_tool_prepare_param_float(PHYSICAL_CONST_degree_to_radian(10.0f)); - BCL_tool_prepare_param_float(1.0f * 60.0f); + BCL_tool_prepare_param_float(FDIR_PARAMETERS_rough_three_axis_rw_div_limit_rad); + BCL_tool_prepare_param_float(FDIR_PARAMETERS_rough_three_axis_rw_div_time_limit_s); BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_APP_AOCS_MM_SET_THREE_AXIS_THRESHOLD); // RW X ON @@ -57,7 +60,7 @@ void BCL_load_rough_three_axis_to_rough_three_axis_rw(void) BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_MM_FINISH_TRANSITION); // 自動モード遷移ON - timing_sec += (5 * 60); + timing_sec += FDIR_PARAMETERS_rough_three_axis_rw_start_mode_manager_time_s; BCL_tool_prepare_param_uint8(1); BCL_tool_register_cmd(OBCT_sec2cycle(timing_sec), Cmd_CODE_APP_AOCS_MM_SET_AUTO_MODE_TRANSITION); } diff --git a/src/src_user/Settings/Modes/mode_definitions.c b/src/src_user/Settings/Modes/mode_definitions.c index cb707764..a0df7a5a 100644 --- a/src/src_user/Settings/Modes/mode_definitions.c +++ b/src/src_user/Settings/Modes/mode_definitions.c @@ -7,7 +7,7 @@ #include -#include "../../TlmCmd/block_command_definitions.h" +#include // モードごとのTLを指定 void MD_load_mode_list(void) diff --git a/src/src_user/Settings/SatelliteParameters/Sample/attitude_control_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/attitude_control_parameters.c new file mode 100644 index 00000000..535dbc05 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/attitude_determination_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/attitude_determination_parameters.c new file mode 100644 index 00000000..22799983 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/attitude_target_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/attitude_target_parameters.c new file mode 100644 index 00000000..8599e62b --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/component_selector_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/component_selector_parameters.c new file mode 100644 index 00000000..4c87628d --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/fdir_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/fdir_parameters.c new file mode 100644 index 00000000..e1d326a9 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/ina260_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/ina260_parameters.c new file mode 100644 index 00000000..49dce5a4 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/mpu9250_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/mpu9250_parameters.c new file mode 100644 index 00000000..fede6c2c --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/nanossoc_d60_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/nanossoc_d60_parameters.c new file mode 100644 index 00000000..fcccd4b6 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/oem7600_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/oem7600_parameters.c new file mode 100644 index 00000000..e14ee8f2 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/orbit_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/orbit_parameters.c index a0145e06..29bc19ee 100644 --- a/src/src_user/Settings/SatelliteParameters/Sample/orbit_parameters.c +++ b/src/src_user/Settings/SatelliteParameters/Sample/orbit_parameters.c @@ -4,9 +4,48 @@ */ #include +#include +#include // Time const double ORBIT_PARAMETERS_reference_jday = 2459932.000; // 2022/12/18 12:00:00 -// Orbit +// 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/src/src_user/Settings/SatelliteParameters/Sample/rm3100_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/rm3100_parameters.c new file mode 100644 index 00000000..7439e422 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/rw0003_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/rw0003_parameters.c new file mode 100644 index 00000000..61bcfda9 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/sagitta_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/sagitta_parameters.c new file mode 100644 index 00000000..9cd7c3b8 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/stim210_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/stim210_parameters.c new file mode 100644 index 00000000..50e0172c --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/Sample/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/src/src_user/Settings/SatelliteParameters/Sample/structure_parameters.c b/src/src_user/Settings/SatelliteParameters/Sample/structure_parameters.c index ede07bff..3f6d3896 100644 --- a/src/src_user/Settings/SatelliteParameters/Sample/structure_parameters.c +++ b/src/src_user/Settings/SatelliteParameters/Sample/structure_parameters.c @@ -5,4 +5,10 @@ #include -const double STRUCTURE_PARAMETERS_mass_sc_kg = 10; +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/src/src_user/Settings/SatelliteParameters/attitude_control_parameters.h b/src/src_user/Settings/SatelliteParameters/attitude_control_parameters.h new file mode 100644 index 00000000..a139e897 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/attitude_control_parameters.h @@ -0,0 +1,102 @@ +/** + * @file attitude_control_parameters.h + * @brief 姿勢制御関連の衛星固有パラメータを管理する + */ + +#ifndef ATTITUDE_CONTROL_PARAMETERS_H_ +#define ATTITUDE_CONTROL_PARAMETERS_H_ + +#include +#include +#include +#include + +// Bdot +extern const float ATTITUDE_CONTROL_PARAMETERS_bdot_control_gain[PHYSICAL_CONST_THREE_DIM]; //!< Control gain for B-dot +extern const uint32_t ATTITUDE_CONTROL_PARAMETERS_bdot_minimum_time_derivative_step_ms; //!< Minimum interval for magnetic field derivative [ms] +extern const uint32_t ATTITUDE_CONTROL_PARAMETERS_bdot_mtq_output_time_length_ms; //!< Keep time for MTQ ON as an actuation [ms] + +// Sun Pointing +// Target +extern const SUN_POINTING_AXIS_ID ATTITUDE_CONTROL_PARAMETERS_sun_pointing_axis_id; //!< Sun pointing target axis ID +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_spin_rate_around_sun_rad_s; //!< Sun pointing target spin rate around sun direction [rad/s] +// Gain +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_x; //!< Sun pointing attitude gain body X axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_y; //!< Sun pointing attitude gain body Y axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_z; //!< Sun pointing attitude gain body Z axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_x; //!< Sun pointing attitude rate gain body X axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_y; //!< Sun pointing attitude rate gain body Y axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_z; //!< Sun pointing attitude rate gain body Z axis +// MTQ control settings +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_direct_feedback_angle_rad; //!< Sun pointing direct feedback max angle [rad] +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_direct_feedback_rate_rad_s; //!< Sun pointing direct feedback max angular rate [rad_s] +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_mtq_allowable_error_ratio_transient; //!< Sun pointing MTQ allowable error in transient phase +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_correction_gain_transient; //!< Sun pointing correction gain in transient phase +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_mtq_allowable_error_ratio_stable; //!< Sun pointing MTQ allowable error in stable phase +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_correction_gain_stable; //!< Sun pointing correction gain in stable phase +// Integral control setting +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_integral_angle_rad; //!< Sun pointing maximum integral angle [rad] +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_angle_to_run_integral_control_rad; //!< Sun pointing maximum angle to run integral control [rad] +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_integral_control_permission_angle_rad; //!< Sun pointing integral control permission angle [rad] +// Spin control setting +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_acceptable_angle_error_to_spin_up_rad; //!< Sun pointing acceptable angle error to start spin-up control [rad] +// Output torque Low Pass Filter(LPF) setting +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_sample_freq_Hz; //!< Sun pointing sampling frequency for both LPF [Hz] +// Output torque LPF (2nd order filter) +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_cutoff_freq_Hz; //!< Sun pointing output LPF cutoff frequency for cross spin axis [Hz] +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_cutoff_freq_spin_axis_Hz; //!< Sun pointing output LPF cutoff frequency for spin axis [Hz] +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_damping_factor; //!< Sun pointing output LPF damping factor +// Spin up LPF (1st order filter) +extern const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_spin_rate_cutoff_freq_Hz; //!< Sun pointing spin up LPF cutoff frequency [Hz] + +// Three Axis Control with MTQ +// Gain +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_x; //!< Three Axis Control MTQ attitude gain body X axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_y; //!< Three Axis Control MTQ attitude gain body Y axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_z; //!< Three Axis Control MTQ attitude gain body Z axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_x; //!< Three Axis Control MTQ attitude rate gain body X axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_y; //!< Three Axis Control MTQ attitude rate gain body Y axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_z; //!< Three Axis Control MTQ attitude rate gain body Z axis +// MTQ control settings +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_direct_feedback_angle_rad; //!< Three Axis Control direct feedback max angle [rad] +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_direct_feedback_rate_rad_s; //!< Three Axis Control direct feedback max angular rate [rad_s] +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_mtq_allowable_error_ratio_transient; //!< Three Axis Control MTQ allowable error in transient phase +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_correction_gain_transient; //!< Three Axis Control correction gain in transient phase +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_mtq_allowable_error_ratio_stable; //!< Three Axis Control MTQ allowable error in stable phase +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_correction_gain_stable; //!< Three Axis Control correction gain in stable phase +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_acceptable_angle_error_as_stable_rad; //!< Three Axis Control acceptable angle error as stable [rad] +// Integral control setting +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_integral_angle_rad; //!< Three Axis Control maximum integral angle [rad] +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_angle_to_run_integral_control_rad; //!< Three Axis Control maximum angle to run integral control [rad] +// Output torque Low Pass Filter(LPF) setting +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_sample_freq_Hz; //!< Three Axis Control sampling frequency for both LPF [Hz] +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_trq_cutoff_freq_Hz; //!< Three Axis Control output LPF cutoff frequency for cross spin axis [Hz] +extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_trq_damping_factor; //!< Three Axis Control output LPF damping factor + +// Three Axis Control with RW +// Gain +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_x; //!< Three Axis Control RW attitude gain body X axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_y; //!< Three Axis Control RW attitude gain body Y axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_z; //!< Three Axis Control RW attitude gain body Z axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_x; //!< Three Axis Control RW attitude rate gain body X axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_y; //!< Three Axis Control RW attitude rate gain body Y axis +extern const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_z; //!< Three Axis Control RW attitude rate gain body Z axis + +// Unloading +extern const float ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_upper_threshold_rad_s; //!< Unloading upper threshold [rad/s] +extern const float ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_lower_threshold_rad_s; //!< Unloading lower threshold [rad/s] +extern const float ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_target_rad_s; //!< Unloading target [rad/s] +extern const float ATTITUDE_CONTROL_PARAMETERS_unloading_control_gain; //!< Unloading gain +extern const APP_UNLOADING_EXEC ATTITUDE_CONTROL_PARAMETERS_unloading_exec_is_enable; //!< Unloading execution enable flag + +// Control Torques +extern const AOCS_MANAGER_CONSTANT_TORQUE_PERMISSION ATTITUDE_CONTROL_PARAMETERS_constant_torque_permission; //!< Constant torque correction permission +extern const float ATTITUDE_CONTROL_PARAMETERS_constant_torque_body_Nm[PHYSICAL_CONST_THREE_DIM]; //!< Constant torque [Nm] +extern const float ATTITUDE_CONTROL_PARAMETERS_internal_torque_max_body_Nm[PHYSICAL_CONST_THREE_DIM]; //!< Maximum output torque for internal torque [Nm] +extern const float ATTITUDE_CONTROL_PARAMETERS_external_torque_max_body_Nm[PHYSICAL_CONST_THREE_DIM]; //!< Maximum output torque for external torque [Nm] + +// Target Setting parameters +extern const float ATTITUDE_CONTROL_PARAMETERS_limit_angular_velocity_rad_s; //!< Limit of angular velocity target error [rad/s] +extern const float ATTITUDE_CONTROL_PARAMETERS_limit_maneuver_angle_rad; //!< Limit of angle target error [rad] + +#endif // ATTITUDE_CONTROL_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/attitude_determination_parameters.h b/src/src_user/Settings/SatelliteParameters/attitude_determination_parameters.h new file mode 100644 index 00000000..46ff26bc --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/attitude_determination_parameters.h @@ -0,0 +1,31 @@ +/** + * @file attitude_determination_parameters.h + * @brief 姿勢決定系に関する衛星固有パラメータを管理する + */ + +#ifndef ATTITUDE_DETERMINATION_PARAMETERS_H_ +#define ATTITUDE_DETERMINATION_PARAMETERS_H_ + +#include +#include +#include + +// Rough Three Axis Determination +extern const APP_RTAD_METHOD ATTITUDE_DETERMINATION_PARAMETERS_rtad_method; //!< Rough three axis determination method +extern const float ATTITUDE_DETERMINATION_PARAMETERS_q_method_sun_vec_weight; //!< Q-method sun vector weight (0.0f ~ 1.0f) + +// Fine Three Axis Determination +extern const APP_FTAD_METHOD ATTITUDE_DETERMINATION_PARAMETERS_ftad_method; //!< Fine three axis determination method + +// STT-Gyro Extended Kalman Filter +// Observation noise model of Gyro sensor +extern const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_noise_standard_deviation_compo_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< EKF gyro sensor random noise standard deviation @ component frame [rad/s] +extern const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_walk_standard_deviation_compo_rad_s2[PHYSICAL_CONST_THREE_DIM]; //!< EKF gyro sensor random walk standard deviation @ component frame [rad/s2] +extern const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_walk_time_constant_s; //!< EKF gyro sensor random walk time constant [s] +// Observation noise model of Star sensor +extern const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_stt_standard_deviation_compo_rad[PHYSICAL_CONST_THREE_DIM]; //!< EKF star sensor random noise standard deviation @ component frame [rad] +// Process noise model +extern const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_process_noise_covariance_attitude; //!< Process noise covariance for attitude +extern const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_process_noise_covariance_attitude_rate; //!< Process noise covariance for attitude rate + +#endif // ATTITUDE_DETERMINATION_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/attitude_target_parameters.h b/src/src_user/Settings/SatelliteParameters/attitude_target_parameters.h new file mode 100644 index 00000000..effae009 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/attitude_target_parameters.h @@ -0,0 +1,32 @@ +/** + * @file attitude_target_parameters.h + * @brief 姿勢目標の衛星固有パラメータを管理する + */ + +#ifndef ATTITUDE_TARGET_PARAMETERS_H_ +#define ATTITUDE_TARGET_PARAMETERS_H_ + +#include +#include +#include + +// Target Calculation Mode +extern const APP_TARGET_ATT_CALC_MODE ATTITUDE_TARGET_PARAMETERS_mode; //!< Attitude target mode + +// Manual mode target +extern const Quaternion ATTITUDE_TARGET_PARAMETERS_quaternion_target_i2t; //!< Target Quaternion + +// Target calculation from orbit +// Main target +extern const APP_TAFO_TARGET_DIRECITON ATTITUDE_TARGET_PARAMETERS_main_target_direction; //!< Main target +extern const float ATTITUDE_TARGET_PARAMETERS_vec_to_main_target_body[PHYSICAL_CONST_THREE_DIM]; //!< Main direction at body frame +// Sub target +extern const APP_TAFO_TARGET_DIRECITON ATTITUDE_TARGET_PARAMETERS_sub_target_direction; //!< Sub target +extern const float ATTITUDE_TARGET_PARAMETERS_vec_to_sub_target_body[PHYSICAL_CONST_THREE_DIM]; //!< Sub direction at body frame +// Offset angle +extern const MATRIX33_ROTATION_AXIS ATTITUDE_TARGET_PARAMETERS_offset_angle_axis; //!< Offset angle axis +extern const float ATTITUDE_TARGET_PARAMETERS_offset_angle_rad; //!< Offset angle [m] +// Target on earth surface +extern const float ATTITUDE_TARGET_PARAMETERS_target_lla_rad_m[PHYSICAL_CONST_THREE_DIM]; //!< Target as latitude [rad], longitude [rad], altitude [m] + +#endif // ATTITUDE_TARGET_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/component_selector_parameters.h b/src/src_user/Settings/SatelliteParameters/component_selector_parameters.h new file mode 100644 index 00000000..5534688c --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/component_selector_parameters.h @@ -0,0 +1,14 @@ +/** + * @file component_selector_parameters.h + * @brief コンポセレクタに関する衛星固有パラメータを管理する + */ + +#ifndef COMPONENT_SELECTOR_PARAMETERS_H_ +#define COMPONENT_SELECTOR_PARAMETERS_H_ + +#include +#include + +extern const APP_MAG_SELECTOR_STATE COMPONENT_SELECTOR_PARAMETERS_initial_selected_magnetometer; //!< Initial selected magnetometer + +#endif // COMPONENT_SELECTOR_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/fdir_parameters.h b/src/src_user/Settings/SatelliteParameters/fdir_parameters.h new file mode 100644 index 00000000..857371e6 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/fdir_parameters.h @@ -0,0 +1,190 @@ +/** + * @file structure_parameters.h + * @brief 衛星構造に関する衛星固有パラメータを管理する + */ + +#ifndef FDIR_PARAMETERS_H_ +#define FDIR_PARAMETERS_H_ + +#include +#include + +// Mode Manager +// Bdot +extern const float FDIR_PARAMETERS_ang_vel_conv_limit_rad_s; //!< Angular velocity convergence detection limit [rad/s] +extern const float FDIR_PARAMETERS_ang_vel_conv_time_limit_s; //!< Angular velocity convergence detection time limit [s] +extern const float FDIR_PARAMETERS_ang_vel_norm_increase_limit_rad_s; //!< Angular velocity increase anomaly detection limit [rad/s] +extern const float FDIR_PARAMETERS_ang_vel_anomaly_detection_period_s; //!< Angular velocity anomaly detection period [s] +extern const uint32_t FDIR_PARAMETERS_bdot_start_mode_manager_time_s; //!< Bdot start auto mode transition time [s] +// Sun pointing control divergence anomaly +extern const float FDIR_PARAMETERS_sun_angle_div_limit_rad; //!< Sun pointing divergence detection limit [rad] +extern const float FDIR_PARAMETERS_sun_angle_div_time_limit_s; //!< Sun pointing divergence detection time limit [s] +extern const uint32_t FDIR_PARAMETERS_sun_pointing_start_mode_manager_time_s; //!< Sun pointing start auto mode transition time [s] +// Rough three axis control with MTQ divergence anomaly +extern const float FDIR_PARAMETERS_rough_three_axis_mtq_div_limit_rad; //!< Three axis control divergence detection limit [rad] +extern const float FDIR_PARAMETERS_rough_three_axis_mtq_div_time_limit_s; //!< Three axis control divergence detection time limit [s] +extern const uint32_t FDIR_PARAMETERS_rough_three_axis_mtq_start_mode_manager_time_s; //!< Rough Three Axis with MTQ start auto mode transition time [s] +// Rough three axis control with RW divergence anomaly +extern const float FDIR_PARAMETERS_rough_three_axis_rw_div_limit_rad; //!< Three axis control divergence detection limit [rad] +extern const float FDIR_PARAMETERS_rough_three_axis_rw_div_time_limit_s; //!< Three axis control divergence detection time limit [s] +extern const uint32_t FDIR_PARAMETERS_rough_three_axis_rw_start_mode_manager_time_s; //!< Rough Three Axis with RW start auto mode transition time [s] +// Fine three axis control divergence anomaly +extern const float FDIR_PARAMETERS_fine_three_axis_div_limit_rad; //!< Three axis control divergence detection limit [rad] +extern const float FDIR_PARAMETERS_fine_three_axis_div_time_limit_s; //!< Three axis control divergence detection time limit [s] +extern const uint32_t FDIR_PARAMETERS_fine_three_axis_start_mode_manager_time_s; //!< Fine Three Axis with RW start auto mode transition time [s] +// Sensor invisible anomaly +extern const float FDIR_PARAMETERS_sun_invisible_time_limit_s; //!< Sun invisible anomaly detection time limit [s] +extern const float FDIR_PARAMETERS_stt_invisible_time_limit_s; //!< STT invisible anomaly detection time limit [s] + + +// S/W over current detection +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_pic_mA; //!< S/W over current detection threshold for PIC [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_stim210_mA; //!< S/W over current detection threshold for STIM210 [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_sagitta_mA; //!< S/W over current detection threshold for SAGITTA [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_oem7600_mA; //!< S/W over current detection threshold for OEM7600 [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rm3100_mA; //!< S/W over current detection threshold for RM3100 [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_nanossoc_d60_mA; //!< S/W over current detection threshold for nanoSSOC D60 [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_mtq_mA; //!< S/W over current detection threshold for MTQ [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rw0003_x_mA; //!< S/W over current detection threshold for RW003 X-axis [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rw0003_y_mA; //!< S/W over current detection threshold for RW003 Y-axis [mA] +extern const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rw0003_z_mA; //!< S/W over current detection threshold for RW003 Z-axis [mA] +// Event handler settings +// STIM210 +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_stim210; //!< S/W over current detection event handler reset count threshold for STIM210 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_stim210_ms; //!< S/W over current detection event handler reset time threshold for STIM210 [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_stim210; //!< S/W over current detection event handler power off count threshold for STIM210 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_stim210_ms; //!< S/W over current detection event handler power off time threshold for STIM210 [ms] +// Sagitta +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_sagitta; //!< S/W over current detection event handler reset count threshold for SAGITTA +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_sagitta_ms; //!< S/W over current detection event handler reset time threshold for SAGITTA [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_sagitta; //!< S/W over current detection event handler power off count threshold for SAGITTA +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_sagitta_ms; //!< S/W over current detection event handler power off time threshold for SAGITTA [ms] +// OEM7600 +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_oem7600; //!< S/W over current detection event handler reset count threshold for OEM7600 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_oem7600_ms; //!< S/W over current detection event handler reset time threshold for OEM7600 [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_oem7600; //!< S/W over current detection event handler power off count threshold for OEM7600 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_oem7600_ms; //!< S/W over current detection event handler power off time threshold for OEM7600 [ms] +// RM3100 +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rm3100; //!< S/W over current detection event handler reset count threshold for RM3100 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rm3100_ms; //!< S/W over current detection event handler reset time threshold for RM3100 [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rm3100; //!< S/W over current detection event handler power off count threshold for RM3100 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rm3100_ms; //!< S/W over current detection event handler power off time threshold for RM3100 [ms] +// nanoSSOC D60 +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_nanossoc_d60; //!< S/W over current detection event handler reset count threshold for nanoSSOC D60 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_nanossoc_d60_ms; //!< S/W over current detection event handler reset time threshold for nanoSSOC D60 [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_nanossoc_d60; //!< S/W over current detection event handler power off count threshold for nanoSSOC D60 +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_nanossoc_d60_ms; //!< S/W over current detection event handler power off time threshold for nanoSSOC D60 [ms] +// MTQ +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_mtq; //!< S/W over current detection event handler reset count threshold for MTQ +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_mtq_ms; //!< S/W over current detection event handler reset time threshold for MTQ [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_mtq; //!< S/W over current detection event handler power off count threshold for MTQ +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_mtq_ms; //!< S/W over current detection event handler power off time threshold for MTQ [ms] +// RW +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_x; //!< S/W over current detection event handler reset count threshold for RW0003 X +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_x_ms; //!< S/W over current detection event handler reset time threshold for RW0003 X [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_x; //!< S/W over current detection event handler power off count threshold for RW0003 X +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_x_ms; //!< S/W over current detection event handler power off time threshold for RW0003 X [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_y; //!< S/W over current detection event handler reset count threshold for RW0003 Y +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_y_ms; //!< S/W over current detection event handler reset time threshold for RW0003 Y [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_y; //!< S/W over current detection event handler power off count threshold for RW0003 Y +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_y_ms; //!< S/W over current detection event handler power off time threshold for RW0003 Y [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_z; //!< S/W over current detection event handler reset count threshold for RW0003 Z +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_z_ms; //!< S/W over current detection event handler reset time threshold for RW0003 Z [ms] +extern const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_z; //!< S/W over current detection event handler power off count threshold for RW0003 Z +extern const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_z_ms; //!< S/W over current detection event handler power off time threshold for RW0003 Z [ms] + +// 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. +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_pic_V; //!< H/W over current detection threshold for PIC [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_stim210_V; //!< H/W over current detection threshold for STIM210 [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_sagitta_V; //!< H/W over current detection threshold for SAGITTA [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_oem7600_V; //!< H/W over current detection threshold for OEM7600 [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_rm3100_V; //!< H/W over current detection threshold for RM3100 [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_nanossoc_d60_V; //!< H/W over current detection threshold for nanoSSOC D60 [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_mtq_V; //!< H/W over current detection threshold for MTQ [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_x_V; //!< H/W over current detection threshold for RW003 X-axis [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_y_V; //!< H/W over current detection threshold for RW003 Y-axis [V] +extern const float FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_z_V; //!< H/W over current detection threshold for RW003 Z-axis [V] +// Event handler settings +// STIM210 +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_stim210; //!< H/W over current detection event handler reset count threshold for STIM210 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_stim210_ms; //!< H/W over current detection event handler reset time threshold for STIM210 [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_stim210; //!< H/W over current detection event handler power off count threshold for STIM210 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_stim210_ms; //!< H/W over current detection event handler power off time threshold for STIM210 [ms] +// Sagitta +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_sagitta; //!< H/W over current detection event handler reset count threshold for SAGITTA +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_sagitta_ms; //!< H/W over current detection event handler reset time threshold for SAGITTA [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_sagitta; //!< H/W over current detection event handler power off count threshold for SAGITTA +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_sagitta_ms; //!< H/W over current detection event handler power off time threshold for SAGITTA [ms] +// OEM7600 +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_oem7600; //!< H/W over current detection event handler reset count threshold for OEM7600 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_oem7600_ms; //!< H/W over current detection event handler reset time threshold for OEM7600 [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_oem7600; //!< H/W over current detection event handler power off count threshold for OEM7600 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_oem7600_ms; //!< H/W over current detection event handler power off time threshold for OEM7600 [ms] +// RM3100 +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rm3100; //!< H/W over current detection event handler reset count threshold for RM3100 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rm3100_ms; //!< H/W over current detection event handler reset time threshold for RM3100 [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rm3100; //!< H/W over current detection event handler power off count threshold for RM3100 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rm3100_ms; //!< H/W over current detection event handler power off time threshold for RM3100 [ms] +// nanoSSOC D60 +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_nanossoc_d60; //!< H/W over current detection event handler reset count threshold for nanoSSOC D60 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_nanossoc_d60_ms; //!< H/W over current detection event handler reset time threshold for nanoSSOC D60 [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_nanossoc_d60; //!< H/W over current detection event handler power off count threshold for nanoSSOC D60 +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_nanossoc_d60_ms; //!< H/W over current detection event handler power off time threshold for nanoSSOC D60 [ms] +// MTQ +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_mtq; //!< H/W over current detection event handler reset count threshold for MTQ +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_mtq_ms; //!< H/W over current detection event handler reset time threshold for MTQ [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_mtq; //!< H/W over current detection event handler power off count threshold for MTQ +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_mtq_ms; //!< H/W over current detection event handler power off time threshold for MTQ [ms] +// RW +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_x; //!< H/W over current detection event handler reset count threshold for RW0003 X +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_x_ms; //!< H/W over current detection event handler reset time threshold for RW0003 X [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_x; //!< H/W over current detection event handler power off count threshold for RW0003 X +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_x_ms; //!< H/W over current detection event handler power off time threshold for RW0003 X [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_y; //!< H/W over current detection event handler reset count threshold for RW0003 Y +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_y_ms; //!< H/W over current detection event handler reset time threshold for RW0003 Y [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_y; //!< H/W over current detection event handler power off count threshold for RW0003 Y +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_y_ms; //!< H/W over current detection event handler power off time threshold for RW0003 Y [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_z; //!< H/W over current detection event handler reset count threshold for RW0003 Z +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_z_ms; //!< H/W over current detection event handler reset time threshold for RW0003 Z [ms] +extern const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_z; //!< H/W over current detection event handler power off count threshold for RW0003 Z +extern const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_z_ms; //!< H/W over current detection event handler power off time threshold for RW0003 Z [ms] + +// Telemetry anomaly +// MPU9250 +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_mp9250; //!< TLM error detection event handler reset count threshold for MPU9250 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_mp9250_ms; //!< TLM error detection event handler reset time threshold for MPU9250 [ms] +// RM3100 +// Use same value for all RM3100s (Users can also change the value with command for each RM3100) +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rm3100; //!< TLM error detection event handler reset count threshold for RM3100 AOBC +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rm3100_ms; //!< TLM error detection event handler reset time threshold for RM3100 AOBC [ms] +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_rm3100; //!< TLM error detection event handler switch sensor count threshold for RM3100 AOBC +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_rm3100_ms; //!< TLM error detection event handler switch sensor time threshold for RM3100 AOBC [ms] +// nanoSSOC D60 +// Use same value for all sun sensors (Users can also change the value with command for each sun sensors) +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; //!< TLM error detection event handler reset count threshold for nanoSSOC D60 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; //!< TLM error detection event handler reset time threshold for nanoSSOC D60 [ms] +// STIM210 +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_stim210; //!< TLM error detection event handler reset count threshold for STIM210 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_stim210_ms; //!< TLM error detection event handler reset time threshold for STIM210 [ms] +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_stim210; //!< TLM error detection event handler switch sensor count threshold for STIM210 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_stim210_ms; //!< TLM error detection event handler switch sensor time threshold for STIM210 [ms] +// Sagitta +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_sagitta; //!< TLM error detection event handler reset count threshold for Sagitta +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_sagitta_ms; //!< TLM error detection event handler reset time threshold for Sagitta [ms] +// OEM7600 +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_oem7600; //!< TLM error detection event handler reset count threshold for OEM7600 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_oem7600_ms; //!< TLM error detection event handler reset time threshold for OEM7600 [ms] +// RW0003 +// Use same value for all RWs (Users can also change the value with command for each RW) +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; //!< TLM error detection event handler reset count threshold for RW0003 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; //!< TLM error detection event handler reset time threshold for RW0003 [ms] +// INA260 +// Use same value for all current sensors (Users can also change the value with command for each current sensor) +extern const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; //!< TLM error detection event handler reset count threshold for INA260 +extern const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; //!< TLM error detection event handler reset time threshold for INA260 [ms] + +// Temperature anomaly +// TBI + +#endif // FDIR_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/ina260_parameters.h b/src/src_user/Settings/SatelliteParameters/ina260_parameters.h new file mode 100644 index 00000000..5585d58e --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/ina260_parameters.h @@ -0,0 +1,71 @@ +/** + * @file ina260_parameters.h + * @brief INA260に関する衛星固有パラメータを管理する + */ + +#ifndef INA260_PARAMETERS_H_ +#define INA260_PARAMETERS_H_ + +#include + +// PIC +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_pic_averaging_mode; //!< Averaging mode for PIC +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_pic_voltage_conversion_time; //!< Voltage conversion time for PIC +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_pic_current_conversion_time; //!< Current conversion time for PIC +extern const float INA260_PARAMETERS_pic_hw_over_current_threshold_mA; //!< H/W over current threshold for PIC [mA] + +// STIM210 +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_stim210_averaging_mode; //!< Averaging mode for STIM210 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_stim210_voltage_conversion_time; //!< Voltage conversion time for STIM210 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_stim210_current_conversion_time; //!< Current conversion time for STIM210 +extern const float INA260_PARAMETERS_stim210_hw_over_current_threshold_mA; //!< H/W over current threshold for STIM210 [mA] + +// SAGITTA +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_sagitta_averaging_mode; //!< Averaging mode for SAGITTA +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_sagitta_voltage_conversion_time; //!< Voltage conversion time for SAGITTA +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_sagitta_current_conversion_time; //!< Current conversion time for SAGITTA +extern const float INA260_PARAMETERS_sagitta_hw_over_current_threshold_mA; //!< H/W over current threshold for SAGITTA [mA] + +// OEM7600 +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_oem7600_averaging_mode; //!< Averaging mode for OEM7600 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_oem7600_voltage_conversion_time; //!< Voltage conversion time for OEM7600 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_oem7600_current_conversion_time; //!< Current conversion time for OEM7600 +extern const float INA260_PARAMETERS_oem7600_hw_over_current_threshold_mA; //!< H/W over current threshold for OEM7600 [mA] + +// RM3100 +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_rm3100_averaging_mode; //!< Averaging mode for RM3100 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rm3100_voltage_conversion_time; //!< Voltage conversion time for RM3100 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rm3100_current_conversion_time; //!< Current conversion time for RM3100 +extern const float INA260_PARAMETERS_rm3100_hw_over_current_threshold_mA; //!< H/W over current threshold for RM3100 [mA] + +// NanoSSOC-D60 +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_nanossoc_d60_averaging_mode; //!< Averaging mode for NanoSSOC-D60 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_nanossoc_d60_voltage_conversion_time; //!< Voltage conversion time for NanoSSOC-D60 +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_nanossoc_d60_current_conversion_time; //!< Current conversion time for NanoSSOC-D60 +extern const float INA260_PARAMETERS_nanossoc_d60_hw_over_current_threshold_mA; //!< H/W over current threshold for NanoSSOC-D60 [mA] + +// MTQ +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_mtq_averaging_mode; //!< Averaging mode for MTQ +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_mtq_voltage_conversion_time; //!< Voltage conversion time for MTQ +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_mtq_current_conversion_time; //!< Current conversion time for MTQ +extern const float INA260_PARAMETERS_mtq_hw_over_current_threshold_mA; //!< H/W over current threshold for MTQ [mA] + +// RW0003 X +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_rw0003_x_averaging_mode; //!< Averaging mode for RW0003 X +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_x_voltage_conversion_time; //!< Voltage conversion time for RW0003 X +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_x_current_conversion_time; //!< Current conversion time for RW0003 X +extern const float INA260_PARAMETERS_rw0003_x_hw_over_current_threshold_mA; //!< H/W over current threshold for RW0003 X [mA] + +// RW0003 Y +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_rw0003_y_averaging_mode; //!< Averaging mode for RW0003 Y +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_y_voltage_conversion_time; //!< Voltage conversion time for RW0003 Y +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_y_current_conversion_time; //!< Current conversion time for RW0003 Y +extern const float INA260_PARAMETERS_rw0003_y_hw_over_current_threshold_mA; //!< H/W over current threshold for RW0003 Y [mA] + +// RW0003 Z +extern const INA260_AVERAGING_MODE INA260_PARAMETERS_rw0003_z_averaging_mode; //!< Averaging mode for RW0003 Z +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_z_voltage_conversion_time; //!< Voltage conversion time for RW0003 Z +extern const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_z_current_conversion_time; //!< Current conversion time for RW0003 Z +extern const float INA260_PARAMETERS_rw0003_z_hw_over_current_threshold_mA; //!< H/W over current threshold for RW0003 Z [mA] + +#endif // INA260_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/mpu9250_parameters.h b/src/src_user/Settings/SatelliteParameters/mpu9250_parameters.h new file mode 100644 index 00000000..421adccb --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/mpu9250_parameters.h @@ -0,0 +1,47 @@ +/** + * @file mpu9250_parameters.h + * @brief MPU9250に関する衛星固有パラメータを管理する + */ + +#ifndef MPU9250_PARAMETERS_H_ +#define MPU9250_PARAMETERS_H_ + +#include +#include +#include + +// Constant value +#define MPU9250_PARAMETERS_kNumCoeffTempCalib (2) //!< Number of coefficient for calibration. This value cannot be changed since it relates Tlm/Cmd definition. + +// Magnetometer bias +extern const float MPU9250_PARAMETERS_mag_bias_compo_nT[PHYSICAL_CONST_THREE_DIM]; //!< Magnetic field observation bias @ component frame [nT] + +// Gyro Bias and scale factor temperature calibration +extern const float MPU9250_PARAMETERS_temperature_range_high_degC; //!< Temperature range high [degC] +extern const float MPU9250_PARAMETERS_temperature_range_low_degC; //!< Temperature range low [degC] +extern const float MPU9250_PARAMETERS_bias_coeff_compo_x[MPU9250_PARAMETERS_kNumCoeffTempCalib]; //!< Bias coefficients @ component frame X axis +extern const float MPU9250_PARAMETERS_scale_factor_coeff_compo_x[MPU9250_PARAMETERS_kNumCoeffTempCalib]; //!< Scale Factor coefficients @ component frame X axis +extern const float MPU9250_PARAMETERS_bias_coeff_compo_y[MPU9250_PARAMETERS_kNumCoeffTempCalib]; //!< Bias coefficients @ component frame Y axis +extern const float MPU9250_PARAMETERS_scale_factor_coeff_compo_y[MPU9250_PARAMETERS_kNumCoeffTempCalib]; //!< Scale Factor coefficients @ component frame Y axis +extern const float MPU9250_PARAMETERS_bias_coeff_compo_z[MPU9250_PARAMETERS_kNumCoeffTempCalib]; //!< Bias coefficients @ component frame Z axis +extern const float MPU9250_PARAMETERS_scale_factor_coeff_compo_z[MPU9250_PARAMETERS_kNumCoeffTempCalib]; //!< Scale Factor coefficients @ component frame Z axis + +// Magnetometer filter +// 1st order Low Pass Filter +extern const float MPU9250_PARAMETERS_mag_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM]; //!< Cut off frequency for magnetometer filter [Hz] +// Spike filter +extern const uint8_t MPU9250_PARAMETERS_mag_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept +extern const uint8_t MPU9250_PARAMETERS_mag_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning +extern const float MPU9250_PARAMETERS_mag_spike_reject_threshold_nT[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold [nT] +extern const float MPU9250_PARAMETERS_mag_spike_amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input [nT] + +// Gyro filter +// 1st order Low Pass Filter +extern const float MPU9250_PARAMETERS_gyro_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM]; //!< Cut off frequency for gyro filter [Hz] +// Spike filter +extern const uint8_t MPU9250_PARAMETERS_gyro_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept +extern const uint8_t MPU9250_PARAMETERS_gyro_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning +extern const float MPU9250_PARAMETERS_gyro_spike_reject_threshold_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold [rad/s] +extern const float MPU9250_PARAMETERS_gyro_spike_amplitude_limit_to_accept_as_step_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input [rad/s] + +#endif // MPU9250_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/nanossoc_d60_parameters.h b/src/src_user/Settings/SatelliteParameters/nanossoc_d60_parameters.h new file mode 100644 index 00000000..544b4344 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/nanossoc_d60_parameters.h @@ -0,0 +1,27 @@ +/** + * @file nanossoc_d60_parameters.h + * @brief nanossoc-D60に関する衛星固有パラメータを管理する + */ + +#ifndef NANOSSOC_D60_PARAMETERS_H_ +#define NANOSSOC_D60_PARAMETERS_H_ + +#include + +// Frame conversion +extern const Quaternion NANOSSOC_D60_PARAMETERS_py_quaternion_c2b; //!< Frame conversion quaternion for PY sun sensor +extern const Quaternion NANOSSOC_D60_PARAMETERS_my_quaternion_c2b; //!< Frame conversion quaternion for MY sun sensor +extern const Quaternion NANOSSOC_D60_PARAMETERS_pz_quaternion_c2b; //!< Frame conversion quaternion for PZ sun sensor +extern const Quaternion NANOSSOC_D60_PARAMETERS_mz_quaternion_c2b; //!< Frame conversion quaternion for MZ sun sensor + +// Spike Filter +extern uint8_t NANOSSOC_D60_PARAMETERS_spike_filter_config_count_limit_to_accept; //!< Count limit to accept +extern uint8_t NANOSSOC_D60_PARAMETERS_spike_filter_config_count_limit_to_reject_continued_warning; //!< Count limit to reject continued warning +extern float NANOSSOC_D60_PARAMETERS_spike_filter_config_reject_threshold_rad; //!< Reject threshold [rad] +extern float NANOSSOC_D60_PARAMETERS_spike_filter_config_amplitude_limit_to_accept_as_step_rad; //!< Amplitude limit to accept as step input [rad] + +// Sun intensity threshold +extern float NANOSSOC_D60_PARAMETERS_sun_intensity_lower_threshold_percent; //!< Sun intensity lower threshold [%] +extern float NANOSSOC_D60_PARAMETERS_sun_intensity_upper_threshold_percent; //!< Sun intensity upper threshold [%] + +#endif // NANOSSOC_D60_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/oem7600_parameters.h b/src/src_user/Settings/SatelliteParameters/oem7600_parameters.h new file mode 100644 index 00000000..af36ff8e --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/oem7600_parameters.h @@ -0,0 +1,22 @@ +/** + * @file oem7600_parameters.h + * @brief OEM7600に関する衛星固有パラメータを管理する + */ + +#ifndef OEM7600_PARAMETERS_H_ +#define OEM7600_PARAMETERS_H_ + +#include + +// Spike Filter +extern uint8_t OEM7600_PARAMETERS_position_spike_filter_config_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept about position +extern uint8_t OEM7600_PARAMETERS_position_spike_filter_config_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning about position +extern double OEM7600_PARAMETERS_position_spike_filter_config_reject_threshold_m[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold about position [m] +extern double OEM7600_PARAMETERS_position_spike_filter_config_amplitude_limit_to_accept_as_step_m[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input about position [m] + +extern uint8_t OEM7600_PARAMETERS_velocity_spike_filter_config_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept about velocity +extern uint8_t OEM7600_PARAMETERS_velocity_spike_filter_config_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning about velocity +extern double OEM7600_PARAMETERS_velocity_spike_filter_config_reject_threshold_m_s[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold about velocity [m/s] +extern double OEM7600_PARAMETERS_velocity_spike_filter_config_amplitude_limit_to_accept_as_step_m_s[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input about velocity [m/s] + +#endif // OEM7600_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/orbit_parameters.h b/src/src_user/Settings/SatelliteParameters/orbit_parameters.h index e39b8f6f..afe7c513 100644 --- a/src/src_user/Settings/SatelliteParameters/orbit_parameters.h +++ b/src/src_user/Settings/SatelliteParameters/orbit_parameters.h @@ -11,7 +11,44 @@ // Time extern const double ORBIT_PARAMETERS_reference_jday; //!< Reference time for orbit calculation [Julian day] -// Orbit +// Orbit Calculator extern const APP_ORBIT_CALC_METHOD ORBIT_PARAMETERS_orbit_calculation_method; //!< Orbit calculation method +// Kepler Orbit +extern const float ORBIT_PARAMETERS_kepler_semi_major_axis_km; //!< Semi-major axis for Kepler Propagator [km] +extern const float ORBIT_PARAMETERS_kepler_eccentricity; //!< Eccentricity for Kepler Propagator +extern const float ORBIT_PARAMETERS_kepler_inclination_rad; //!< Inclination for Kepler Propagator [rad] +extern const float ORBIT_PARAMETERS_kepler_raan_rad; //!< RAAN (Right Ascension of Ascending Node) for Kepler Propagator [rad] +extern const float ORBIT_PARAMETERS_kepler_arg_perigee_rad; //!< Argment of perigee for Kepler Propagator [rad] +extern const double ORBIT_PARAMETERS_kepler_epoch_jday; //!< Epoch for Kepler Propagator [Julian day] + +// TLE for SGP4 +// 1st line +extern const uint8_t ORBIT_PARAMETERS_tle_epoch_year; //!< Epoch year in TLE 1st line for SGP4 Propagator +extern const double ORBIT_PARAMETERS_tle_epoch_day; //!< Epoch day in TLE 1st line for SGP4 Propagator +extern const float ORBIT_PARAMETERS_tle_b_star; //!< B-star in TLE 1st line for SGP4 Propagator +// 2nd line +extern const float ORBIT_PARAMETERS_tle_inclination_deg; //!< Inclination in TLE 2nd line for SGP4 Propagator [deg] +extern const float ORBIT_PARAMETERS_tle_raan_deg; //!< RAAN (Right Ascension of Ascending Node) in TLE 2nd line for SGP4 Propagator [deg] +extern const float ORBIT_PARAMETERS_tle_eccentricity; //!< Eccentricity in TLE 2nd line for SGP4 Propagator [-] +extern const float ORBIT_PARAMETERS_tle_arg_perigee_deg; //!< Argment of perigee in TLE 2nd line for SGP4 Propagator [deg] +extern const float ORBIT_PARAMETERS_tle_mean_anomaly_deg; //!< Mean anomaly in TLE 2nd line for SGP4 Propagator [deg] +extern const float ORBIT_PARAMETERS_tle_mean_motion_rpd; //!< Mean motion in TLE 2nd line for SGP4 Propagator [RPD] + +// GPS-R Orbit Propagator +// Initial orbital elements +extern const float ORBIT_PARAMETERS_gpsr_semi_major_axis_km; //!< Semi-major axis for GPS-R Orbit Propagator [km] +extern const float ORBIT_PARAMETERS_gpsr_eccentricity; //!< Eccentricity for GPS-R Orbit Propagator +extern const float ORBIT_PARAMETERS_gpsr_inclination_rad; //!< Inclination for GPS-R Orbit Propagator [rad] +extern const float ORBIT_PARAMETERS_gpsr_raan_rad; //!< RAAN (Right Ascension of Ascending Node) for GPS-R Orbit Propagator [rad] +extern const float ORBIT_PARAMETERS_gpsr_arg_perigee_rad; //!< Argment of perigee for GPS-R Orbit Propagator [rad] +extern const double ORBIT_PARAMETERS_gpsr_epoch_jday; //!< Epoch for GPS-R Orbit Propagator [Julian day] +// Threshold +extern const float ORBIT_PARAMETERS_gpsr_threshold_semi_major_axis_km; //!< Semi-major axis threshold for GPS-R Orbit Propagator [km] +extern const float ORBIT_PARAMETERS_gpsr_threshold_eccentricity; //!< Eccentricity threshold for GPS-R Orbit Propagator +extern const float ORBIT_PARAMETERS_gpsr_threshold_inclination_rad; //!< Inclination threshold for GPS-R Orbit Propagator [rad] +extern const float ORBIT_PARAMETERS_gpsr_threshold_raan_rad; //!< RAAN (Right Ascension of Ascending Node) threshold for GPS-R Orbit Propagator [rad] +extern const float ORBIT_PARAMETERS_gpsr_threshold_arg_perigee_rad; //!< Argment of perigee threshold for GPS-R Orbit Propagator [rad] +extern const double ORBIT_PARAMETERS_gpsr_threshold_epoch_jday; //!< Epoch threshold for GPS-R Orbit Propagator [Julian day] + #endif // ORBIT_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/parameter_setting_macro.h b/src/src_user/Settings/SatelliteParameters/parameter_setting_macro.h new file mode 100644 index 00000000..b4154fc5 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/parameter_setting_macro.h @@ -0,0 +1,25 @@ +/** + * @file parameter_setting_macro.h + * @brief 衛星固有パラメータの数値設定で使われるマクロをまとめたヘッダファイル. + * @note staticな衛星固有パラメータの初期化子は定数式か文字列リテラルである必要があり,ここに関数式を含めることができない. + * 関数式を呼び出した場合,initializer element is not constantビルドエラーとなる. + */ + +#ifndef PARAMETER_SETTING_MACRO_H_ +#define PARAMETER_SETTING_MACRO_H_ + +#include + +/** + * @brief degからradに変換する関数マクロ + * @param[in] deg : 角度[deg] +*/ +#define PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(degree) ((degree) * (MATH_CONST_PI) / 180.0f) + +/** + * @brief RPMからrad/sに変換する関数マクロ + * @param[in] rpm : 回転角速度[rpm] +*/ +#define PARAMETER_SETTING_MACRO_RPM_TO_RADIAN_SEC(rpm) ((rpm) * MATH_CONST_PI / 30.0f) + +#endif // PARAMETER_SETTING_MACRO_H_ diff --git a/src/src_user/Settings/SatelliteParameters/rm3100_parameters.h b/src/src_user/Settings/SatelliteParameters/rm3100_parameters.h new file mode 100644 index 00000000..d18ebbcd --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/rm3100_parameters.h @@ -0,0 +1,41 @@ +/** + * @file rm3100_parameters.h + * @brief RM3100に関する衛星固有パラメータを管理する + */ + +#ifndef RM3100_PARAMETERS_H_ +#define RM3100_PARAMETERS_H_ + +#include +#include +#include +#include + +// AOBC RM3100 +// Magnetometer bias +extern const float RM3100_PARAMETERS_mag_aobc_bias_compo_nT[PHYSICAL_CONST_THREE_DIM]; //!< Magnetic field observation bias for AOBC RM3100 @ component frame [nT] +// Magnetometer filter +// 1st order Low Pass Filter +extern const float RM3100_PARAMETERS_mag_aobc_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM]; //!< Cut off frequency for magnetometer filter [Hz] +// Spike filter +extern const uint8_t RM3100_PARAMETERS_mag_aobc_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept +extern const uint8_t RM3100_PARAMETERS_mag_aobc_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning +extern const float RM3100_PARAMETERS_mag_aobc_spike_reject_threshold_nT[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold [nT] +extern const float RM3100_PARAMETERS_mag_aobc_spike_amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input [nT] + + +// External RM3100 +// Frame conversion +extern const Quaternion RM3100_PARAMETERS_mag_ext_quaternion_c2b; //!< Frame conversion Quaternion from component to body frame +// Magnetometer bias +extern const float RM3100_PARAMETERS_mag_ext_bias_compo_nT[PHYSICAL_CONST_THREE_DIM]; //!< Magnetic field observation bias for external RM3100 @ component frame [nT] +// Magnetometer filter +// 1st order Low Pass Filter +extern const float RM3100_PARAMETERS_mag_ext_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM]; //!< Cut off frequency for magnetometer filter [Hz] +// Spike filter +extern const uint8_t RM3100_PARAMETERS_mag_ext_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept +extern const uint8_t RM3100_PARAMETERS_mag_ext_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning +extern const float RM3100_PARAMETERS_mag_ext_spike_reject_threshold_nT[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold [nT] +extern const float RM3100_PARAMETERS_mag_ext_spike_amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input [nT] + +#endif // RM3100_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/rw0003_parameters.h b/src/src_user/Settings/SatelliteParameters/rw0003_parameters.h new file mode 100644 index 00000000..5ca0b275 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/rw0003_parameters.h @@ -0,0 +1,18 @@ +/** + * @file rw0003_parameters.h + * @brief RW0.003に関する衛星固有パラメータを管理する + */ + +#ifndef RW0003_PARAMETERS_H_ +#define RW0003_PARAMETERS_H_ + +#include +#include + +// Spike Filter +extern uint8_t RW0003_PARAMETERS_spike_filter_config_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept +extern uint8_t RW0003_PARAMETERS_spike_filter_config_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning +extern double RW0003_PARAMETERS_spike_filter_config_reject_threshold_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold [rad/s] +extern double RW0003_PARAMETERS_spike_filter_config_amplitude_limit_to_accept_as_step_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input [rad/s] + +#endif // RW0003_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/sagitta_parameters.h b/src/src_user/Settings/SatelliteParameters/sagitta_parameters.h new file mode 100644 index 00000000..56f566cf --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/sagitta_parameters.h @@ -0,0 +1,18 @@ +/** + * @file sagitta_parameters.h + * @brief SAGITTAに関する衛星固有パラメータを管理する + */ + +#ifndef SAGITTA_PARAMETERS_H_ +#define SAGITTA_PARAMETERS_H_ + +#include +#include + +// Spike Filter +extern uint8_t SAGITTA_PARAMETERS_q_i2b_spike_filter_config_count_limit_to_accept; //!< Count limit to accept +extern uint8_t SAGITTA_PARAMETERS_q_i2b_spike_filter_config_count_limit_to_reject_continued_warning; //!< Count limit to reject continued warning +extern double SAGITTA_PARAMETERS_q_i2b_spike_filter_config_reject_threshold_rad; //!< Reject threshold [rad] +extern double SAGITTA_PARAMETERS_q_i2b_spike_filter_config_amplitude_limit_to_accept_as_step_rad; //!< Amplitude limit to accept as step input [rad] + +#endif // SAGITTA_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/stim210_parameters.h b/src/src_user/Settings/SatelliteParameters/stim210_parameters.h new file mode 100644 index 00000000..98772ff2 --- /dev/null +++ b/src/src_user/Settings/SatelliteParameters/stim210_parameters.h @@ -0,0 +1,34 @@ +/** + * @file stim210_parameters.h + * @brief STIM210に関する衛星固有パラメータを管理する + */ + +#ifndef STIM210_PARAMETERS_H_ +#define STIM210_PARAMETERS_H_ + +#include +#include + +// Constant value +#define STIM210_PARAMETERS_kNumCoeffTempCalib (2) //!< Number of coefficient for calibration. This value cannot be changed since it relates Tlm/Cmd definition. + +// Gyro Bias and scale factor temperature calibration +extern const float STIM210_PARAMETERS_temperature_range_high_degC; //!< Temperature range high [degC] +extern const float STIM210_PARAMETERS_temperature_range_low_degC; //!< Temperature range low [degC] +extern const float STIM210_PARAMETERS_bias_coeff_compo_x[STIM210_PARAMETERS_kNumCoeffTempCalib]; //!< Bias coefficients @ component frame X axis +extern const float STIM210_PARAMETERS_scale_factor_coeff_compo_x[STIM210_PARAMETERS_kNumCoeffTempCalib]; //!< Scale Factor coefficients @ component frame X axis +extern const float STIM210_PARAMETERS_bias_coeff_compo_y[STIM210_PARAMETERS_kNumCoeffTempCalib]; //!< Bias coefficients @ component frame Y axis +extern const float STIM210_PARAMETERS_scale_factor_coeff_compo_y[STIM210_PARAMETERS_kNumCoeffTempCalib]; //!< Scale Factor coefficients @ component frame Y axis +extern const float STIM210_PARAMETERS_bias_coeff_compo_z[STIM210_PARAMETERS_kNumCoeffTempCalib]; //!< Bias coefficients @ component frame Z axis +extern const float STIM210_PARAMETERS_scale_factor_coeff_compo_z[STIM210_PARAMETERS_kNumCoeffTempCalib]; //!< Scale Factor coefficients @ component frame Z axis + +// Gyro filter +// 1st order Low Pass Filter +extern const float STIM210_PARAMETERS_gyro_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM]; //!< Cut off frequency for gyro filter [Hz] +// Spike filter +extern const uint8_t STIM210_PARAMETERS_gyro_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to accept +extern const uint8_t STIM210_PARAMETERS_gyro_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM]; //!< Count limit to reject continued warning +extern const float STIM210_PARAMETERS_gyro_spike_reject_threshold_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< Reject threshold [rad/s] +extern const float STIM210_PARAMETERS_gyro_spike_amplitude_limit_to_accept_as_step_rad_s[PHYSICAL_CONST_THREE_DIM]; //!< Amplitude limit to accept as step input [rad/s] + +#endif // STIM210_PARAMETERS_H_ diff --git a/src/src_user/Settings/SatelliteParameters/structure_parameters.h b/src/src_user/Settings/SatelliteParameters/structure_parameters.h index e3d3df9e..d42500b2 100644 --- a/src/src_user/Settings/SatelliteParameters/structure_parameters.h +++ b/src/src_user/Settings/SatelliteParameters/structure_parameters.h @@ -6,6 +6,12 @@ #ifndef STRUCTURE_PARAMETERS_H_ #define STRUCTURE_PARAMETERS_H_ -extern const double STRUCTURE_PARAMETERS_mass_sc_kg; //!< Spacecraft mass [kg] +#include + +extern const float STRUCTURE_PARAMETERS_mass_sc_kg; //!< Spacecraft mass [kg] + +extern const float STRUCTURE_PARAMETERS_rmm_sc_body_Am2[PHYSICAL_CONST_THREE_DIM]; //!< Spacecraft Residual Magnetic Moment at body-fixed frame [Am2] + +extern const float STRUCTURE_PARAMETERS_inertia_tensor_sc_body_kgm2[PHYSICAL_CONST_THREE_DIM][PHYSICAL_CONST_THREE_DIM]; //!< Spacecraft inertia tensor @ body-fixed frame [kg m2] #endif // STRUCTURE_PARAMETERS_H_ diff --git a/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_hw_oc.c b/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_hw_oc.c index 3e1e09d8..c2438d2c 100644 --- a/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_hw_oc.c +++ b/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_hw_oc.c @@ -5,9 +5,12 @@ */ #include "event_handler_rules.h" #include -#include "../../../TlmCmd/block_command_definitions.h" -#include "../event_logger_group.h" -#include "../../../Applications/DriverInstances/di_ina260.h" +#include +#include +#include + +// Satellite Parameters +#include void EH_load_rule_hw_oc(void) { @@ -18,8 +21,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_stim210_ms; settings.deploy_bct_id = BC_RESET_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_STIM210, &settings); @@ -30,8 +33,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_stim210_ms; settings.deploy_bct_id = BC_POWER_OFF_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_STIM210_BROKEN, &settings); @@ -41,8 +44,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_sagitta; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_sagitta_ms; settings.deploy_bct_id = BC_RESET_SAGITTA; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_SAGITTA, &settings); @@ -53,8 +56,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_sagitta; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_sagitta_ms; settings.deploy_bct_id = BC_POWER_OFF_SAGITTA; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_SAGITTA_BROKEN, &settings); @@ -64,8 +67,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_oem7600; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_oem7600_ms; settings.deploy_bct_id = BC_RESET_OEM7600; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_OEM7600, &settings); @@ -76,8 +79,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_oem7600; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_oem7600_ms; settings.deploy_bct_id = BC_POWER_OFF_OEM7600; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_OEM7600_BROKEN, &settings); @@ -87,8 +90,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_RESET_RM3100; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RM3100, &settings); @@ -99,8 +102,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_POWER_OFF_RM3100; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RM3100_BROKEN, &settings); @@ -110,8 +113,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms =FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_NANOSSOC_D60, &settings); @@ -122,8 +125,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_POWER_OFF_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_NANOSSOC_D60_BROKEN, &settings); @@ -133,8 +136,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_mtq; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_mtq_ms; settings.deploy_bct_id = BC_RESET_MTQ; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_MTQ, &settings); @@ -145,8 +148,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_mtq; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_mtq_ms; settings.deploy_bct_id = BC_POWER_OFF_MTQ; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_MTQ_BROKEN, &settings); @@ -156,8 +159,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_x; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_x_ms; settings.deploy_bct_id = BC_RESET_RWX; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RW0003X, &settings); @@ -168,8 +171,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_x; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_x_ms; settings.deploy_bct_id = BC_POWER_OFF_RWX; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RW0003X_BROKEN, &settings); @@ -179,8 +182,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_y; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_y_ms; settings.deploy_bct_id = BC_RESET_RWY; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RW0003Y, &settings); @@ -191,8 +194,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_y; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_y_ms; settings.deploy_bct_id = BC_POWER_OFF_RWY; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RW0003Y_BROKEN, &settings); @@ -202,8 +205,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_z; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_z_ms; settings.deploy_bct_id = BC_RESET_RWZ; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RW0003Z, &settings); @@ -214,8 +217,8 @@ void EH_load_rule_hw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_z; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_z_ms; settings.deploy_bct_id = BC_POWER_OFF_RWZ; settings.is_active = 0; EH_register_rule(EH_RULE_HW_OC_RW0003Z_BROKEN, &settings); diff --git a/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_sw_oc.c b/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_sw_oc.c index 51153f39..088898e4 100644 --- a/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_sw_oc.c +++ b/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_sw_oc.c @@ -5,9 +5,12 @@ */ #include "event_handler_rules.h" #include -#include "../../../TlmCmd/block_command_definitions.h" -#include "../event_logger_group.h" -#include "../../../Applications/DriverInstances/di_ina260.h" +#include +#include +#include + +// Satellite Parameters +#include void EH_load_rule_sw_oc(void) { @@ -18,8 +21,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_stim210_ms; settings.deploy_bct_id = BC_RESET_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_STIM210, &settings); @@ -30,8 +33,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_stim210_ms; settings.deploy_bct_id = BC_POWER_OFF_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_STIM210_BROKEN, &settings); @@ -41,8 +44,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_sagitta; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_sagitta_ms; settings.deploy_bct_id = BC_RESET_SAGITTA; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_SAGITTA, &settings); @@ -53,8 +56,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_sagitta; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_sagitta_ms; settings.deploy_bct_id = BC_POWER_OFF_SAGITTA; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_SAGITTA_BROKEN, &settings); @@ -64,8 +67,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_oem7600; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_oem7600_ms; settings.deploy_bct_id = BC_RESET_OEM7600; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_OEM7600, &settings); @@ -76,8 +79,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_oem7600; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_oem7600_ms; settings.deploy_bct_id = BC_POWER_OFF_OEM7600; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_OEM7600_BROKEN, &settings); @@ -87,8 +90,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_RESET_RM3100; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RM3100, &settings); @@ -99,8 +102,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_POWER_OFF_RM3100; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RM3100_BROKEN, &settings); @@ -110,8 +113,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms =FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_NANOSSOC_D60, &settings); @@ -122,8 +125,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_POWER_OFF_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_NANOSSOC_D60_BROKEN, &settings); @@ -133,8 +136,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_mtq; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_mtq_ms; settings.deploy_bct_id = BC_RESET_MTQ; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_MTQ, &settings); @@ -145,8 +148,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_mtq; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_mtq_ms; settings.deploy_bct_id = BC_POWER_OFF_MTQ; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_MTQ_BROKEN, &settings); @@ -156,8 +159,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_x; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_x_ms; settings.deploy_bct_id = BC_RESET_RWX; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RW0003X, &settings); @@ -168,8 +171,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_x; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_x_ms; settings.deploy_bct_id = BC_POWER_OFF_RWX; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RW0003X_BROKEN, &settings); @@ -179,8 +182,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_y; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_y_ms; settings.deploy_bct_id = BC_RESET_RWY; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RW0003Y, &settings); @@ -191,8 +194,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_z; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_z_ms; settings.deploy_bct_id = BC_POWER_OFF_RWY; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RW0003Y_BROKEN, &settings); @@ -202,8 +205,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_LOW; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_z; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_z_ms; settings.deploy_bct_id = BC_RESET_RWZ; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RW0003Z, &settings); @@ -214,8 +217,8 @@ void EH_load_rule_sw_oc(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_z; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_z_ms; settings.deploy_bct_id = BC_POWER_OFF_RWZ; settings.is_active = 0; EH_register_rule(EH_RULE_SW_OC_RW0003Z_BROKEN, &settings); diff --git a/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_tlmcmd.c b/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_tlmcmd.c index 8f33acdb..77273981 100644 --- a/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_tlmcmd.c +++ b/src/src_user/Settings/System/EventHandlerRules/event_handler_rule_tlmcmd.c @@ -5,16 +5,19 @@ */ #include "event_handler_rules.h" #include -#include "../../../TlmCmd/block_command_definitions.h" -#include "../event_logger_group.h" -#include "../../../Applications/DriverInstances/di_mpu9250.h" -#include "../../../Applications/DriverInstances/di_rm3100.h" -#include "../../../Applications/DriverInstances/di_nanossoc_d60.h" -#include "../../../Applications/DriverInstances/di_stim210.h" -#include "../../../Applications/DriverInstances/di_sagitta.h" -#include "../../../Applications/DriverInstances/di_oem7600.h" -#include "../../../Applications/DriverInstances/di_rw0003.h" -#include "../../../Applications/DriverInstances/di_ina260.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Satellite Parameters +#include void EH_load_rule_tlmcmd(void) { @@ -26,8 +29,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_mp9250; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_mp9250_ms; settings.deploy_bct_id = BC_RESET_MPU9250; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_MPU9250, &settings); @@ -38,8 +41,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_RESET_RM3100; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RM3100_ON_AOBC, &settings); @@ -50,8 +53,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_SELECT_RM3100_EXTERNAL; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RM3100_ON_AOBC_BROKEN, &settings); @@ -62,8 +65,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 1000; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_RESET_RM3100; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RM3100_EXTERNAL, &settings); @@ -74,8 +77,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_rm3100; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_rm3100_ms; settings.deploy_bct_id = BC_SELECT_RM3100_ON_AOBC; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RM3100_EXTERNAL_BROKEN, &settings); @@ -86,8 +89,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_NANOSSOC_D60_PY, &settings); @@ -98,8 +101,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_NANOSSOC_D60_MY, &settings); @@ -110,8 +113,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_NANOSSOC_D60_PZ, &settings); @@ -122,8 +125,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_NANOSSOC_D60_MZ, &settings); @@ -134,8 +137,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_stim210_ms; settings.deploy_bct_id = BC_RESET_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_STIM210, &settings); @@ -146,8 +149,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_stim210_ms; settings.deploy_bct_id = BC_POWER_OFF_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_STIM210_BROKEN, &settings); @@ -158,8 +161,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_sagitta; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_sagitta_ms; settings.deploy_bct_id = BC_RESET_SAGITTA; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_SAGITTA, &settings); @@ -170,8 +173,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_oem7600; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_oem7600_ms; settings.deploy_bct_id = BC_RESET_OEM7600; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_OEM7600, &settings); @@ -182,8 +185,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; settings.deploy_bct_id = BC_RESET_RWX; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RWX, &settings); @@ -194,8 +197,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; settings.deploy_bct_id = BC_RESET_RWY; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RWY, &settings); @@ -206,8 +209,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 10; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; settings.deploy_bct_id = BC_RESET_RWZ; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_RWZ, &settings); @@ -218,8 +221,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_PIC, &settings); @@ -229,8 +232,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_STIM210, &settings); @@ -240,8 +243,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_SAGITTA, &settings); @@ -251,8 +254,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_OEM7600, &settings); @@ -262,8 +265,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_RM3100, &settings); @@ -273,8 +276,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_NANOSSOC_D60, &settings); @@ -284,8 +287,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_MTQ, &settings); @@ -295,8 +298,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_RW0003_X, &settings); @@ -306,8 +309,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_RW0003_Y, &settings); @@ -317,8 +320,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 5000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms; settings.deploy_bct_id = BC_RESET_INA260; settings.is_active = 0; EH_register_rule(EH_RULE_TLM_ERROR_INA260_RW0003_Z, &settings); @@ -329,8 +332,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_CHECKSUM_ERROR_NANOSSOC_D60_PY, &settings); @@ -341,8 +344,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_CHECKSUM_ERROR_NANOSSOC_D60_MY, &settings); @@ -353,8 +356,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_CHECKSUM_ERROR_NANOSSOC_D60_PZ, &settings); @@ -365,8 +368,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 250; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms; settings.deploy_bct_id = BC_RESET_NANOSSOC_D60; settings.is_active = 0; EH_register_rule(EH_RULE_CHECKSUM_ERROR_NANOSSOC_D60_MZ, &settings); @@ -377,8 +380,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_stim210_ms; settings.deploy_bct_id = BC_RESET_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_CRC_ERROR_STIM210, &settings); @@ -389,8 +392,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_EH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CUMULATIVE; - settings.condition.count_threshold = 5; - settings.condition.time_threshold_ms = 0; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_stim210; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_stim210_ms; settings.deploy_bct_id = BC_POWER_OFF_STIM210; settings.is_active = 0; EH_register_rule(EH_RULE_CRC_ERROR_STIM210_BROKEN, &settings); @@ -401,8 +404,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_sagitta; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_sagitta_ms; settings.deploy_bct_id = BC_RESET_SAGITTA; settings.is_active = 0; EH_register_rule(EH_RULE_XXHASH_ERROR_SAGITTA, &settings); @@ -413,8 +416,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_oem7600; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_oem7600_ms; settings.deploy_bct_id = BC_RESET_OEM7600; settings.is_active = 0; EH_register_rule(EH_RULE_CRC_ERROR_OEM7600, &settings); @@ -425,8 +428,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; settings.deploy_bct_id = BC_RESET_RWX; settings.is_active = 0; EH_register_rule(EH_RULE_CRC_ERROR_RWX, &settings); @@ -437,8 +440,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; settings.deploy_bct_id = BC_RESET_RWY; settings.is_active = 0; EH_register_rule(EH_RULE_CRC_ERROR_RWY, &settings); @@ -449,8 +452,8 @@ void EH_load_rule_tlmcmd(void) settings.event.err_level = EL_ERROR_LEVEL_HIGH; settings.should_match_err_level = 1; settings.condition.type = EH_RESPONSE_CONDITION_CONTINUOUS; - settings.condition.count_threshold = 100; - settings.condition.time_threshold_ms = 2000; + settings.condition.count_threshold = FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003; + settings.condition.time_threshold_ms = FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms; settings.deploy_bct_id = BC_RESET_RWZ; settings.is_active = 0; EH_register_rule(EH_RULE_CRC_ERROR_RWZ, &settings); diff --git a/src/src_user/Settings/port_config.h b/src/src_user/Settings/port_config.h index 25662ad3..3a639432 100644 --- a/src/src_user/Settings/port_config.h +++ b/src/src_user/Settings/port_config.h @@ -125,4 +125,9 @@ #define I2C_DEVICE_ADDR_INA_RWY (0x48) //!< RW_Y軸用のINA260電流センサ #define I2C_DEVICE_ADDR_INA_RWZ (0x49) //!< RW_Z軸用のINA260電流センサ +// Use user defined I2C address +#ifdef USER_DEFINED_I2C_ADDRESS +#include +#endif + #endif diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_ina260.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_ina260.c index 0b39108b..628b181b 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_ina260.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_ina260.c @@ -1,17 +1,20 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include + +// Satellite Parameters +#include void BCL_load_power_on_ina260() { @@ -24,72 +27,72 @@ void BCL_load_power_on_ina260() // Initialize BCL_tool_prepare_param_uint8(INA260_IDX_PIC); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_pic_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_pic_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_pic_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_STIM210); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_stim210_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_stim210_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_stim210_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_SAGITTA); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_sagitta_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_sagitta_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_sagitta_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_OEM7600); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_oem7600_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_oem7600_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_oem7600_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RM3100); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_1MS); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_1MS); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rm3100_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rm3100_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rm3100_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_NANOSSOC_D60); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_nanossoc_d60_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_nanossoc_d60_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_nanossoc_d60_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_MTQ); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_mtq_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_mtq_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_mtq_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RW0003_X); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_x_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_x_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_x_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RW0003_Y); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_y_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_y_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_y_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RW0003_Z); - BCL_tool_prepare_param_uint8(INA260_AVERAGING_MODE_16); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); - BCL_tool_prepare_param_uint8(INA260_CONVERSION_TIME_140US); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_z_averaging_mode); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_z_voltage_conversion_time); + BCL_tool_prepare_param_uint8(INA260_PARAMETERS_rw0003_z_current_conversion_time); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_INIT); bc_cycle++; @@ -119,52 +122,52 @@ void BCL_load_set_ina260_oc_limit() cycle_t bc_cycle = 1; BCL_tool_prepare_param_uint8(INA260_IDX_PIC); - BCL_tool_prepare_param_float(200.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_pic_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_STIM210); - BCL_tool_prepare_param_float(1000.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_stim210_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_SAGITTA); - BCL_tool_prepare_param_float(500.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_sagitta_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_OEM7600); - BCL_tool_prepare_param_float(1000.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_oem7600_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RM3100); - BCL_tool_prepare_param_float(200.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_rm3100_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_NANOSSOC_D60); - BCL_tool_prepare_param_float(150.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_nanossoc_d60_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_MTQ); - BCL_tool_prepare_param_float(2000.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_mtq_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RW0003_X); - BCL_tool_prepare_param_float(2000.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_rw0003_x_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RW0003_Y); - BCL_tool_prepare_param_float(2000.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_rw0003_y_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; BCL_tool_prepare_param_uint8(INA260_IDX_RW0003_Z); - BCL_tool_prepare_param_float(2000.0f); // mA + BCL_tool_prepare_param_float(INA260_PARAMETERS_rw0003_z_hw_over_current_threshold_mA); BCL_tool_register_cmd(bc_cycle, Cmd_CODE_DI_INA260_SET_OVER_CURRENT_PROTECTION); bc_cycle++; diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_mtq.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_mtq.c index f2f580c6..d43becbf 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_mtq.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_mtq.c @@ -1,17 +1,17 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include void BCL_load_power_on_mtq(void) { diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_nanossoc_d60.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_nanossoc_d60.c index 9e56ed08..2d939c68 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_nanossoc_d60.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_nanossoc_d60.c @@ -1,18 +1,18 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Applications/DriverInstances/di_rm3100.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include +#include void BCL_load_power_on_nanossoc_d60(void) { diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_oem7600.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_oem7600.c index 055ea370..a8c06920 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_oem7600.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_oem7600.c @@ -1,19 +1,19 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_oem7600.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Applications/DriverInstances/di_rm3100.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include +#include +#include void BCL_load_power_on_oem7600(void) { diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rm3100.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rm3100.c index cf6581a2..e9bc2787 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rm3100.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rm3100.c @@ -1,19 +1,19 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_rm3100.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/magnetometer_selector.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include +#include +#include void BCL_load_power_on_rm3100() { diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rw0003.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rw0003.c index b1dcc087..be93318a 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rw0003.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_rw0003.c @@ -1,18 +1,18 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_rw0003.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include +#include void BCL_load_power_on_rwx(void) { diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_sagitta.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_sagitta.c index e7d5a439..40f0a8cb 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_sagitta.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_sagitta.c @@ -1,19 +1,19 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/DriverInstances/di_sagitta.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Applications/DriverInstances/di_rm3100.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" +#include +#include +#include +#include +#include +#include void BCL_load_power_on_sagitta(void) { diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_start_hk_tlm.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_start_hk_tlm.c index c543b007..afb1a157 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_start_hk_tlm.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_start_hk_tlm.c @@ -1,9 +1,9 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include diff --git a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_stim210.c b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_stim210.c index 6223b336..98e39d87 100644 --- a/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_stim210.c +++ b/src/src_user/TlmCmd/NormalBlockCommandDefinition/nbc_stim210.c @@ -1,21 +1,21 @@ #pragma section REPRO #include "nbc_header.h" -#include "../block_command_definitions.h" -#include "../command_definitions.h" -#include "../telemetry_definitions.h" +#include +#include +#include #include #include #include -#include "../../Applications/UserDefined/Power/power_switch_control.h" -#include "../../Applications/UserDefined/AOCS/HardwareDependent/SensorSelectors/gyro_selector.h" -#include "../../Applications/DriverInstances/di_ina260.h" -#include "../../Applications/DriverInstances/di_rm3100.h" -#include "../../Settings/System/EventHandlerRules/event_handler_rules.h" -#include "../../Settings/System/event_logger_group.h" -#include "../../Applications/DriverInstances/di_stim210.h" +#include +#include +#include +#include +#include +#include +#include void BCL_load_power_on_stim210(void) diff --git a/src/src_user/TlmCmd/block_command_definitions.c b/src/src_user/TlmCmd/block_command_definitions.c index 030d409d..821a6bd6 100644 --- a/src/src_user/TlmCmd/block_command_definitions.c +++ b/src/src_user/TlmCmd/block_command_definitions.c @@ -5,33 +5,33 @@ #include // for memcpy #include "command_definitions.h" -#include "../Settings/Modes/Transitions/sl_nop.h" -#include "../Settings/Modes/Transitions/sl_initial.h" -#include "../Settings/Modes/Transitions/sl_bdot.h" -#include "../Settings/Modes/Transitions/sl_rough_sun_pointing.h" -#include "../Settings/Modes/Transitions/sl_rough_three_axis.h" -#include "../Settings/Modes/Transitions/sl_rough_three_axis_rw.h" -#include "../Settings/Modes/Transitions/sl_fine_three_axis.h" +#include +#include +#include +#include +#include +#include +#include -#include "../Settings/Modes/TaskLists/tl_initial.h" -#include "../Settings/Modes/TaskLists/tl_bdot.h" -#include "../Settings/Modes/TaskLists/tl_rough_sun_pointing.h" -#include "../Settings/Modes/TaskLists/tl_rough_three_axis.h" -#include "../Settings/Modes/TaskLists/tl_rough_three_axis_rw.h" -#include "../Settings/Modes/TaskLists/tl_fine_three_axis.h" -#include "../Settings/Modes/TaskLists/tl_gpsr_range_observe.h" +#include +#include +#include +#include +#include +#include +#include -#include "../Settings/Modes/TaskLists/Elements/tl_elem_cdh_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_drivers_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_inertial_ref_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_sun_vector_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_mtq_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_basic_sensor_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_rw_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_rm3100_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_stim210_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_oem7600_update.h" -#include "../Settings/Modes/TaskLists/Elements/tl_elem_stt_update.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include "./NormalBlockCommandDefinition/nbc_header.h" diff --git a/src/src_user/TlmCmd/command_source.h b/src/src_user/TlmCmd/command_source.h index f083a903..72a3262d 100644 --- a/src/src_user/TlmCmd/command_source.h +++ b/src/src_user/TlmCmd/command_source.h @@ -15,7 +15,7 @@ #include #include #include -#include "../Applications/app_headers.h" +#include // #include "telemetry_definitions.h" #endif diff --git a/src/src_user/TlmCmd/user_packet_handler.h b/src/src_user/TlmCmd/user_packet_handler.h index 31539e0a..2ea03bd0 100644 --- a/src/src_user/TlmCmd/user_packet_handler.h +++ b/src/src_user/TlmCmd/user_packet_handler.h @@ -10,7 +10,7 @@ #include #include #include "telemetry_definitions.h" -#include "../Settings/TlmCmd/Ccsds/apid_define.h" +#include /** * @brief PH のユーザー固有部初期化処理