From 46c6a1bc9b793f5d463ad12a70329e826eee3567 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 02:04:01 -0700 Subject: [PATCH 1/7] Refactoring part of how argument of periapsis maneuvers are implemented, adding some tests To account for varying orbital parameters by the time an argument of periapsis change maneuver is actually implemented (compared to initial orbital elements of the satellite), and to try to streamline the user experience more, the maneuver is simply added to the satellite, where it is stashed in a list of maneuvers that are awaiting initialization. When the satellite's internal clock reaches or first surpasses the start time, it is initialized and removed from that list of maneuvers needing initialization. Also, the calibration method previously implemented utilizing mean values has been removed, as I no longer think it's as useful as I did earlier. Also added a couple tests relating to argument of periapsis change maneuvers. --- README.md | 4 +- .../arg_of_periapsis_calibration_input.json | 2 +- include/Satellite.h | 8 +- include/utils.h | 3 +- sim_parameters.json | 7 -- sim_parameters_example.json | 2 +- simulation_setup.cpp | 24 ++---- src/Satellite.cpp | 31 +++++++- src/utils.cpp | 45 +---------- tests/Satellite_tests.cpp | 79 +++++++++++++++++++ 10 files changed, 129 insertions(+), 76 deletions(-) delete mode 100644 sim_parameters.json diff --git a/README.md b/README.md index 631e132..1d01bd4 100644 --- a/README.md +++ b/README.md @@ -32,7 +32,7 @@ - Continuous (low) thrust maneuvers to change argument of perigee - - Note: Thrust profiles of argument of periapsis change maneuvers are calculated assuming a "continuous" maneuver takes place (i.e., a burn arc angle $\alpha = \pi/2$ radians in https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf). Therefore it is not recommended to use this feature outside of parameter ranges where this assumption does not hold. + - Note: Thrust profiles of argument of periapsis change maneuvers are calculated assuming a "continuous" maneuver takes place (i.e., a burn arc angle $\alpha = \pi/2$ radians in https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf). Therefore it is not recommended to use this feature outside of parameter ranges where this assumption does not hold. Maneuvers that take place over a fraction of an orbit are not recommended. ## TO DO @@ -72,6 +72,8 @@ Simulation of zero-inclination orbits isn't currently supported, as the magnitud Calculation of instantaneous orbital angular acceleration does not currently include any contribution from the time derivative of the magnitude of the orbital angular momentum vector. +Loss of propellant mass during burns is not yet accounted for. + Visualization/plotting is done via Gnuplot. The copyright and permission notice of Gnuplot is shown below: Copyright 1986 - 1993, 1998, 2004 Thomas Williams, Colin Kelley diff --git a/example_satellite_input_files/arg_of_periapsis_calibration_input.json b/example_satellite_input_files/arg_of_periapsis_calibration_input.json index 4f17d5c..79b11a7 100644 --- a/example_satellite_input_files/arg_of_periapsis_calibration_input.json +++ b/example_satellite_input_files/arg_of_periapsis_calibration_input.json @@ -1,7 +1,7 @@ { "Inclination": 5, "RAAN": 0, - "Argument of Periapsis": 20, + "Argument of Periapsis": 30, "Eccentricity": 0.1, "Semimajor Axis": 15000, "True Anomaly": 0, diff --git a/include/Satellite.h b/include/Satellite.h index 4fc813f..6f66cba 100644 --- a/include/Satellite.h +++ b/include/Satellite.h @@ -52,6 +52,7 @@ class ThrustProfileLVLH { // Main ref: https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf // // Used Eq. 67 in https://link.springer.com/article/10.1007/s10569-021-10033-9#Sec15 to determine burn angles + // Arguments of periapsis are input in radians arg_of_periapsis_change_thrust_profile = true; t_start_ = t_start; const double alpha = M_PI/2.0; // continous thrust @@ -62,7 +63,7 @@ class ThrustProfileLVLH { const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); const double acceleration = thrust_magnitude/satellite_mass; t_end_ = t_start + delta_V/acceleration; - std::cout << "Transfer time: " << t_end_ << "\n"; + std::cout << "Maneuver duration: " << t_end_ << "\n"; } bool operator==(const ThrustProfileLVLH& input_profile) { return ((t_start_ == input_profile.t_start_) && @@ -163,7 +164,7 @@ class Satellite { std::vector> list_of_ECI_forces_at_this_time_ = {}; std::vector> list_of_body_frame_torques_at_this_time_ = {}; - + std::vector>> maneuvers_awaiting_initiation_ = {}; double drag_surface_area = {0}; // Surface area of satellite used for // atmospheric drag calculations @@ -381,6 +382,9 @@ class Satellite { double get_attitude_val(const std::string input_attitude_val_name); double calculate_orbital_period(); int add_arg_of_periapsis_change_thrust(); + void check_for_maneuvers_to_initialize(); + void add_maneuver(const std::string maneuver_type, const double maneuver_start_time, + const double final_parameter_val, const double thrust_magnitude); }; #endif \ No newline at end of file diff --git a/include/utils.h b/include/utils.h index 5310fa5..cd278cb 100644 --- a/include/utils.h +++ b/include/utils.h @@ -166,6 +166,7 @@ std::pair, std::pair> RK45_step( double input_t_n, double input_epsilon, double input_inclination, double input_arg_of_periapsis, double input_true_anomaly, bool perturbation) { + // std::cout << "In RK45_step, received perturbation bool: " << perturbation << "\n"; // Version for satellite orbital motion time evolution // Implementing RK4(5) method for its adaptive step size // Refs:https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method @@ -515,6 +516,4 @@ void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_ int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double final_orbit_semimajor_axis_km, const double thrust_magnitude, const double transfer_initiation_time = 0); - -double calibrate_mean_val(Satellite satellite_object, const SimParameters& input_sim_parameters, const std::string input_parameter_name); #endif \ No newline at end of file diff --git a/sim_parameters.json b/sim_parameters.json deleted file mode 100644 index 459c8ca..0000000 --- a/sim_parameters.json +++ /dev/null @@ -1,7 +0,0 @@ -{ - "Simulation end time": 25000, - "epsilon": 0.000000000001, - "Initial timestep guess": 1, - "Perturbation": true, - "Drag": false -} \ No newline at end of file diff --git a/sim_parameters_example.json b/sim_parameters_example.json index 14a4218..38addb6 100644 --- a/sim_parameters_example.json +++ b/sim_parameters_example.json @@ -1,6 +1,6 @@ { "Simulation duration": 25000, - "epsilon": 0.000000001, + "epsilon": 0.000000000001, "Initial timestep guess": 1, "Perturbation": true, "Drag": false diff --git a/simulation_setup.cpp b/simulation_setup.cpp index 62a65fb..7cd5886 100644 --- a/simulation_setup.cpp +++ b/simulation_setup.cpp @@ -146,25 +146,17 @@ int main() { // oscillations at the final orbit be close to the target value Satellite arg_periapsis_change_sat("../example_satellite_input_files/arg_of_periapsis_test_input.json"); - Satellite arg_periapsis_change_calibration_sat("../example_satellite_input_files/arg_of_periapsis_calibration_input.json"); - sim_parameters.epsilon = pow(10,-12); - sim_parameters.total_sim_time = 250000; + sim_parameters.epsilon = pow(10,-14); + sim_parameters.total_sim_time = 400000; sim_parameters.perturbation_bool = false; sim_parameters.drag_bool = false; - double set_initial_arg_of_periapsis = arg_periapsis_change_sat.get_orbital_parameter("Argument of Periapsis"); - double mean_val_final = calibrate_mean_val(arg_periapsis_change_calibration_sat,sim_parameters,"Argument of Periapsis"); - t_thrust_start = 25000; - double mean_val_initial = calibrate_mean_val(arg_periapsis_change_sat,sim_parameters,"Argument of Periapsis"); - // NOTE: Make sure the below value matches the argument of periapsis of your calibration satellite. - double final_arg_of_periapsis_deg = 20; - if (final_arg_of_periapsis_deg != arg_periapsis_change_calibration_sat.get_orbital_parameter("Argument of Periapsis")) { - std::cout << "Warning: Entered final argument of periapsis differs from value in calibration satellite object. " - "This will skew the applied offset from the nominal value. Make sure these two argument of periapsis values are equal.\n"; - } - double offset = (final_arg_of_periapsis_deg - mean_val_final) + (set_initial_arg_of_periapsis - mean_val_initial); - double final_arg_of_periapsis = final_arg_of_periapsis_deg * (M_PI/180.0); // rad + + t_thrust_start = 50000; + double final_arg_of_periapsis_deg = 25; + thrust_magnitude = 0.1; // N - arg_periapsis_change_sat.add_LVLH_thrust_profile(t_thrust_start,final_arg_of_periapsis+(offset*M_PI/180.0),thrust_magnitude); + // std::cout << "orbital period: " << arg_periapsis_change_sat.calculate_orbital_period() << "\n"; + arg_periapsis_change_sat.add_maneuver("Argument of Periapsis Change",t_thrust_start,final_arg_of_periapsis_deg,thrust_magnitude); file_name = "Arg of periapsis transfer"; std::vector arg_of_periapsis_transfer_vec = {arg_periapsis_change_sat}; sim_and_plot_orbital_elem_gnuplot(arg_of_periapsis_transfer_vec, sim_parameters, "Argument of Periapsis", file_name); diff --git a/src/Satellite.cpp b/src/Satellite.cpp index ecbd556..6aeebb0 100644 --- a/src/Satellite.cpp +++ b/src/Satellite.cpp @@ -395,6 +395,7 @@ std::pair Satellite::evolve_RK45( const double input_epsilon, const double input_step_size, const bool perturbation, const bool atmospheric_drag, const std::pair drag_elements) { + // std::cout << "In EvolveRK45, received perturbation bool: " << perturbation << "\n"; // perturbation is a flag which, when set to true, currently accounts for J2 // perturbation. @@ -412,7 +413,10 @@ std::pair Satellite::evolve_RK45( // F_10 is the first element, A_p is the second element double input_F_10 = drag_elements.first; double input_A_p = drag_elements.second; - + + // Initialize arg of periapsis change thrust profile from current orbital parameters, + // if there is one that hasn't already been initialized + check_for_maneuvers_to_initialize(); // Add any thrusts from an argument of periapsis change maneuver, if applicable int arg_of_periapsis_code = add_arg_of_periapsis_change_thrust(); @@ -699,4 +703,27 @@ int Satellite::add_arg_of_periapsis_change_thrust() { } } return 0; -} \ No newline at end of file +} +void Satellite::check_for_maneuvers_to_initialize() { + for (size_t maneuver_index = 0; maneuver_index < maneuvers_awaiting_initiation_.size(); maneuver_index++) { + std::pair> maneuver_info = maneuvers_awaiting_initiation_.at(maneuver_index); + const double maneuver_start_time = maneuver_info.second.at(0); + if ((maneuver_start_time <= t_) && (maneuver_info.first == "Argument of Periapsis Change")) { + // Need to initialize this maneuver + const double target_arg_of_periapsis_deg = maneuver_info.second.at(1); + const double target_arg_of_periapsis_rad = target_arg_of_periapsis_deg * (M_PI/180.0); + const double thrust_magnitude = maneuver_info.second.at(2); + ThrustProfileLVLH thrust_profile(maneuver_start_time,target_arg_of_periapsis_rad,thrust_magnitude, + arg_of_periapsis_, eccentricity_, a_, m_); + thrust_profile_list_.push_back(thrust_profile); + maneuvers_awaiting_initiation_.erase(maneuvers_awaiting_initiation_.begin() + maneuver_index); + } + } +} + +void Satellite::add_maneuver(const std::string maneuver_type, const double maneuver_start_time, + const double final_parameter_val, const double thrust_magnitude) { + std::array maneuver_vals = {maneuver_start_time,final_parameter_val,thrust_magnitude}; + std::pair> maneuver_info = {maneuver_type,maneuver_vals}; + maneuvers_awaiting_initiation_.push_back(maneuver_info); + } \ No newline at end of file diff --git a/src/utils.cpp b/src/utils.cpp index 78af8ef..9809c7a 100644 --- a/src/utils.cpp +++ b/src/utils.cpp @@ -353,6 +353,7 @@ std::array RK45_deriv_function_orbit_position_and_velocity( const double input_F_10, const double input_A_p, const double input_A_s, const double input_satellite_mass, const bool perturbation, const bool atmospheric_drag) { + // std::cout << "In RK45 deriv function orbit position and velocity, received perturbation bool: " << perturbation << "\n"; std::array derivative_of_input_y = {}; std::array position_array = {}; std::array velocity_array = {}; @@ -1612,48 +1613,4 @@ int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double transfer_initiation_time, transfer_initiation_time + time_to_burn); } return error_code; -} - -double calibrate_mean_val(Satellite satellite_object, const SimParameters& input_sim_parameters, const std::string input_parameter_name) { - // Objective: help calibrate simulations in context of inherent oscillations of parameters - // Here, the mean value of oscillations will be assumed to be constant (oscillations don't drift up or down over time) - - // Let the simulation run without external applied forces, return mean value of parameter - // Not passing in satellite object by ref so that its internal clock doesn't get altered from its initial value before the actual - // simulations start - - double val = - satellite_object.get_orbital_parameter(input_parameter_name); - double mean_val = val; - size_t num_datapoints = 1; - double current_satellite_time = - satellite_object.get_instantaneous_time(); - - double evolved_val = {0}; - - double timestep_to_use = input_sim_parameters.initial_timestep_guess; - current_satellite_time = satellite_object.get_instantaneous_time(); - while (current_satellite_time < input_sim_parameters.total_sim_time) { - std::pair drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; - std::pair new_timestep_and_error_code = - satellite_object.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - input_sim_parameters.perturbation_bool, - input_sim_parameters.drag_bool, drag_elements); - double new_timestep = new_timestep_and_error_code.first; - int error_code = new_timestep_and_error_code.second; - - if (error_code != 0) { - std::cout << "Error code " << error_code << " detected, halting simulation and returning 0\n"; - return 0.0; - } - timestep_to_use = new_timestep; - evolved_val = - satellite_object.get_orbital_parameter(input_parameter_name); - mean_val += evolved_val; - num_datapoints+=1; - - current_satellite_time = satellite_object.get_instantaneous_time(); - } - mean_val /= num_datapoints; - return mean_val; } \ No newline at end of file diff --git a/tests/Satellite_tests.cpp b/tests/Satellite_tests.cpp index abaaa76..3863fd1 100644 --- a/tests/Satellite_tests.cpp +++ b/tests/Satellite_tests.cpp @@ -340,6 +340,85 @@ TEST(EllipticalOrbitTests, DragTest2) { " After-loop time without drag: " << current_time_nodrag << " and with drag: " << current_time_withdrag << "\n"; } +TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver1) { + Satellite test_satellite("../tests/elliptical_orbit_test_3.json"); + double test_timestep = 0.1; // s + bool perturbation_bool = true; + std::pair new_timestep_and_error_code = + test_satellite.evolve_RK45(epsilon, test_timestep, perturbation_bool); + double next_timestep = new_timestep_and_error_code.first; + int error_code = new_timestep_and_error_code.second; + const double t_thrust_start = 0; + const double initial_arg_of_periapsis_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); + const double initial_arg_of_periapsis_rad = initial_arg_of_periapsis_deg*(M_PI/180.0); + const double target_arg_of_periapsis_deg = initial_arg_of_periapsis_deg + 10; + const double target_arg_of_periapsis_rad = target_arg_of_periapsis_deg*(M_PI/180.0); + const double alpha = M_PI/2.0; // continous thrust + const double sign_of_delta_omega = 1.0; // because in this case, the final arg of periapsis is larger than the initial + const double thrust_magnitude = 0.1; // N + const double mu_Earth = G*mass_Earth; + const double delta_omega_mag = abs(target_arg_of_periapsis_rad - initial_arg_of_periapsis_rad); // = delta_omega / sgn(delta_omega) + const double satellite_a = test_satellite.get_orbital_parameter("Semimajor Axis"); + const double satellite_eccentricity = test_satellite.get_orbital_parameter("Eccentricity"); + const double satellite_mass = test_satellite.get_mass(); + const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); + const double acceleration = thrust_magnitude/satellite_mass; + const double maneuver_length = delta_V/acceleration; + const double total_sim_time = maneuver_length + 10000; + double temp_epsilon = pow(10,-14); + test_satellite.add_maneuver("Argument of Periapsis Change",t_thrust_start,target_arg_of_periapsis_deg,thrust_magnitude); + double current_time = test_satellite.get_instantaneous_time(); + while (current_time < total_sim_time) { + std::pair new_timestep_and_error_code = + test_satellite.evolve_RK45(temp_epsilon, test_timestep, false); + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time = test_satellite.get_instantaneous_time(); + } + double arg_of_periapsis_final_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); + EXPECT_TRUE(abs(arg_of_periapsis_final_deg - target_arg_of_periapsis_deg) < 1); +} + +TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver2) { + Satellite test_satellite("../tests/elliptical_orbit_test_3.json"); + double test_timestep = 0.1; // s + bool perturbation_bool = true; + std::pair new_timestep_and_error_code = + test_satellite.evolve_RK45(epsilon, test_timestep, perturbation_bool); + double next_timestep = new_timestep_and_error_code.first; + int error_code = new_timestep_and_error_code.second; + const double t_thrust_start = 0; + const double initial_arg_of_periapsis_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); + const double initial_arg_of_periapsis_rad = initial_arg_of_periapsis_deg*(M_PI/180.0); + const double target_arg_of_periapsis_deg = initial_arg_of_periapsis_deg - 10; + const double target_arg_of_periapsis_rad = target_arg_of_periapsis_deg*(M_PI/180.0); + const double alpha = M_PI/2.0; // continous thrust + const double sign_of_delta_omega = 1.0; // because in this case, the final arg of periapsis is larger than the initial + const double thrust_magnitude = 0.1; // N + const double mu_Earth = G*mass_Earth; + const double delta_omega_mag = abs(target_arg_of_periapsis_rad - initial_arg_of_periapsis_rad); // = delta_omega / sgn(delta_omega) + const double satellite_a = test_satellite.get_orbital_parameter("Semimajor Axis"); + const double satellite_eccentricity = test_satellite.get_orbital_parameter("Eccentricity"); + const double satellite_mass = test_satellite.get_mass(); + const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); + const double acceleration = thrust_magnitude/satellite_mass; + const double maneuver_length = delta_V/acceleration; + const double total_sim_time = maneuver_length + 10000; + double temp_epsilon = pow(10,-14); + test_satellite.add_maneuver("Argument of Periapsis Change",t_thrust_start,target_arg_of_periapsis_deg,thrust_magnitude); + double current_time = test_satellite.get_instantaneous_time(); + while (current_time < total_sim_time) { + std::pair new_timestep_and_error_code = + test_satellite.evolve_RK45(temp_epsilon, test_timestep, false); + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time = test_satellite.get_instantaneous_time(); + } + double arg_of_periapsis_final_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); + EXPECT_TRUE(abs(arg_of_periapsis_final_deg - target_arg_of_periapsis_deg) < 1); +} // Circular orbit tests From f2a19e514e03de0ca7f9ce0619e0a4673d0d32f3 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 02:12:09 -0700 Subject: [PATCH 2/7] Running clang-format on header files --- .gitignore | 5 ++- include/PhasedArrayGroundStation.h | 64 +++++++++++++++++------------- include/Satellite.h | 52 +++++++++++++++--------- include/utils.h | 62 ++++++++++++++++------------- 4 files changed, 107 insertions(+), 76 deletions(-) diff --git a/.gitignore b/.gitignore index 3ee8715..2e78f26 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,7 @@ build/ .DS_Store .vscode/ -*.png \ No newline at end of file +*.png +src/files_to_format.txt +include/files_to_format.txt +tests/files_to_format.txt \ No newline at end of file diff --git a/include/PhasedArrayGroundStation.h b/include/PhasedArrayGroundStation.h index a3e23c6..532b4c1 100644 --- a/include/PhasedArrayGroundStation.h +++ b/include/PhasedArrayGroundStation.h @@ -1,41 +1,49 @@ #ifndef GROUNDSTATION_HEADER #define GROUNDSTATION_HEADER -#include #include +#include #include + #include "Satellite.h" using Eigen::Vector3d; class PhasedArrayGroundStation { - // Phased array ground station class - public: - double latitude = {0}; - double longitude = {0}; - double height = {0}; - Vector3d ECEF_position_; - double max_beam_angle_from_normal_ = {0}; //deg - int num_beams_ = {0}; - // To enforce the maximum number of satellites a ground station can communicate with at any one time, - // going to create a map where each key is the satellite index of a given satellite (i.e., index in a satellite vector being plotted) - // Each key has a val which is a vector of pairs, where the first element is the start of a time range where the - // ground station is communicating with that satellite, and the second element is the end time for that range - // So communications with satellites are characterized by vectors of time ranges + // Phased array ground station class + public: + double latitude = {0}; + double longitude = {0}; + double height = {0}; + Vector3d ECEF_position_; + double max_beam_angle_from_normal_ = {0}; // deg + int num_beams_ = {0}; + // To enforce the maximum number of satellites a ground station can + // communicate with at any one time, going to create a map where each key is + // the satellite index of a given satellite (i.e., index in a satellite vector + // being plotted) Each key has a val which is a vector of pairs, where the + // first element is the start of a time range where the ground station is + // communicating with that satellite, and the second element is the end time + // for that range So communications with satellites are characterized by + // vectors of time ranges + + std::map>> linked_sats_map_; - std::map>> linked_sats_map_; - - PhasedArrayGroundStation(double latitude, double longitude, double height, double max_beam_angle_from_normal, int num_beams = 1) { - generate_ECEF_position(); - num_beams_ = num_beams; - max_beam_angle_from_normal_ = max_beam_angle_from_normal; - } - void generate_ECEF_position(); - Vector3d get_ECI_position(double input_time); - double distance_to_satellite(Satellite input_satellite); - double angle_to_satellite_from_normal(Satellite input_satellite); - int num_sats_connected_at_this_time(double input_time); - void update_linked_sats_map(const size_t satellite_index, const double connection_time, const double previous_time); - }; + PhasedArrayGroundStation(double latitude, double longitude, double height, + double max_beam_angle_from_normal, + int num_beams = 1) { + generate_ECEF_position(); + num_beams_ = num_beams; + max_beam_angle_from_normal_ = max_beam_angle_from_normal; + } + void generate_ECEF_position(); + Vector3d get_ECI_position(double input_time); + double distance_to_satellite(Satellite input_satellite); + double angle_to_satellite_from_normal(Satellite input_satellite); + int num_sats_connected_at_this_time(double input_time); + void update_linked_sats_map(const size_t satellite_index, + const double connection_time, + const double previous_time); +}; #endif \ No newline at end of file diff --git a/include/Satellite.h b/include/Satellite.h index 6f66cba..1e5528e 100644 --- a/include/Satellite.h +++ b/include/Satellite.h @@ -25,7 +25,8 @@ class ThrustProfileLVLH { double t_end_ = {0}; bool arg_of_periapsis_change_thrust_profile = false; double sign_of_delta_omega = {1}; - double thrust_magnitude_ = {0}; // Only used for argument of periapsis change thrust profiles + double thrust_magnitude_ = { + 0}; // Only used for argument of periapsis change thrust profiles std::array LVLH_force_vec_ = {0, 0, 0}; ThrustProfileLVLH(const double t_start, const double t_end, const std::array LVLH_force_vec) { @@ -45,24 +46,33 @@ class ThrustProfileLVLH { } } ThrustProfileLVLH(const double t_start, const double final_arg_of_periapsis, - const double thrust_magnitude, const double initial_arg_of_periapsis, - const double satellite_eccentricity, const double satellite_a, - const double satellite_mass) { + const double thrust_magnitude, + const double initial_arg_of_periapsis, + const double satellite_eccentricity, + const double satellite_a, const double satellite_mass) { // Thrust profile for continuous-thrust argument of periapsis change // Main ref: https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf - // - // Used Eq. 67 in https://link.springer.com/article/10.1007/s10569-021-10033-9#Sec15 to determine burn angles - // Arguments of periapsis are input in radians + // + // Used Eq. 67 in + // https://link.springer.com/article/10.1007/s10569-021-10033-9#Sec15 to + // determine burn angles Arguments of periapsis are input in radians arg_of_periapsis_change_thrust_profile = true; t_start_ = t_start; - const double alpha = M_PI/2.0; // continous thrust - (final_arg_of_periapsis > initial_arg_of_periapsis) ? sign_of_delta_omega = 1.0 : sign_of_delta_omega = -1.0; + const double alpha = M_PI / 2.0; // continous thrust + (final_arg_of_periapsis > initial_arg_of_periapsis) + ? sign_of_delta_omega = 1.0 + : sign_of_delta_omega = -1.0; thrust_magnitude_ = thrust_magnitude; - const double mu_Earth = G*mass_Earth; - const double delta_omega_mag = abs(final_arg_of_periapsis - initial_arg_of_periapsis); // = delta_omega / sgn(delta_omega) - const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); - const double acceleration = thrust_magnitude/satellite_mass; - t_end_ = t_start + delta_V/acceleration; + const double mu_Earth = G * mass_Earth; + const double delta_omega_mag = + abs(final_arg_of_periapsis - + initial_arg_of_periapsis); // = delta_omega / sgn(delta_omega) + const double delta_V = + (2.0 / 3.0) * sqrt(mu_Earth / satellite_a) * satellite_eccentricity * + delta_omega_mag / + sqrt(1 - satellite_eccentricity * satellite_eccentricity); + const double acceleration = thrust_magnitude / satellite_mass; + t_end_ = t_start + delta_V / acceleration; std::cout << "Maneuver duration: " << t_end_ << "\n"; } bool operator==(const ThrustProfileLVLH& input_profile) { @@ -164,7 +174,8 @@ class Satellite { std::vector> list_of_ECI_forces_at_this_time_ = {}; std::vector> list_of_body_frame_torques_at_this_time_ = {}; - std::vector>> maneuvers_awaiting_initiation_ = {}; + std::vector>> + maneuvers_awaiting_initiation_ = {}; double drag_surface_area = {0}; // Surface area of satellite used for // atmospheric drag calculations @@ -355,8 +366,9 @@ class Satellite { void add_LVLH_thrust_profile( const std::array input_LVLH_thrust_vector, const double input_thrust_start_time, const double input_thrust_end_time); - void add_LVLH_thrust_profile(const double input_thrust_start_time, const double final_arg_of_periapsis, - const double input_thrust_magnitude); + void add_LVLH_thrust_profile(const double input_thrust_start_time, + const double final_arg_of_periapsis, + const double input_thrust_magnitude); void add_bodyframe_torque_profile( const std::array input_bodyframe_direction_unit_vec, const double input_bodyframe_torque_magnitude, @@ -383,8 +395,10 @@ class Satellite { double calculate_orbital_period(); int add_arg_of_periapsis_change_thrust(); void check_for_maneuvers_to_initialize(); - void add_maneuver(const std::string maneuver_type, const double maneuver_start_time, - const double final_parameter_val, const double thrust_magnitude); + void add_maneuver(const std::string maneuver_type, + const double maneuver_start_time, + const double final_parameter_val, + const double thrust_magnitude); }; #endif \ No newline at end of file diff --git a/include/utils.h b/include/utils.h index cd278cb..965a201 100644 --- a/include/utils.h +++ b/include/utils.h @@ -6,8 +6,8 @@ #include #include -#include "Satellite.h" #include "PhasedArrayGroundStation.h" +#include "Satellite.h" using Eigen::Matrix3d; using Eigen::MatrixXd; @@ -16,7 +16,6 @@ using Eigen::Vector4d; using json = nlohmann::json; - struct SimParameters { double initial_timestep_guess = 1; double total_sim_time = 10; @@ -88,9 +87,11 @@ std::array RK4_deriv_function_orbit_position_and_velocity( // template // std::array RK4_step( // const std::array y_n, const double input_step_size, -// std::function(const std::array input_y_vec, +// std::function(const std::array +// input_y_vec, // const double input_spacecraft_mass, -// const std::vector> +// const std::vector> // input_vec_of_force_vectors_in_ECI)> // input_derivative_function, // const double input_spacecraft_mass, @@ -101,7 +102,8 @@ std::array RK4_deriv_function_orbit_position_and_velocity( // const std::vector> // input_vec_of_force_vectors_in_ECI_at_t_and_step = {}) { // // ref: -// // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method +// // +// https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method // std::array y_nplus1 = y_n; // // first, k=1; @@ -148,11 +150,9 @@ std::array RK4_deriv_function_orbit_position_and_velocity( // return y_nplus1; // } -void sim_and_draw_orbit_gnuplot( - std::vector input_satellite_vector, - const SimParameters& input_sim_parameters, - const std::string output_file_name = "output" -); +void sim_and_draw_orbit_gnuplot(std::vector input_satellite_vector, + const SimParameters& input_sim_parameters, + const std::string output_file_name = "output"); template std::pair, std::pair> RK45_step( @@ -166,7 +166,8 @@ std::pair, std::pair> RK45_step( double input_t_n, double input_epsilon, double input_inclination, double input_arg_of_periapsis, double input_true_anomaly, bool perturbation) { - // std::cout << "In RK45_step, received perturbation bool: " << perturbation << "\n"; + // std::cout << "In RK45_step, received perturbation bool: " << perturbation + // << "\n"; // Version for satellite orbital motion time evolution // Implementing RK4(5) method for its adaptive step size // Refs:https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method @@ -206,8 +207,8 @@ std::pair, std::pair> RK45_step( std::array k_vec_at_this_s; for (size_t s_ind = 0; s_ind < k_ind; s_ind++) { for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { - y_n_evaluated_value.at(y_val_ind) += RK_matrix(k_ind, s_ind) * - k_vec_vec.at(s_ind).at(y_val_ind); + y_n_evaluated_value.at(y_val_ind) += + RK_matrix(k_ind, s_ind) * k_vec_vec.at(s_ind).at(y_val_ind); } } std::array derivative_function_output = @@ -291,14 +292,14 @@ std::array convert_cylindrical_to_cartesian( const double input_r_comp, const double input_theta_comp, const double input_z_comp, const double input_theta); void sim_and_plot_orbital_elem_gnuplot( - std::vector input_satellite_vector, + std::vector input_satellite_vector, const SimParameters& input_sim_parameters, const std::string input_orbital_element_name, const std::string file_name = "output"); void sim_and_plot_attitude_evolution_gnuplot( std::vector input_satellite_vector, const SimParameters& input_sim_parameters, - const std::string input_plotted_val_name, + const std::string input_plotted_val_name, const std::string file_name = "output"); Matrix3d rollyawpitch_bodyframe_to_LVLH( @@ -500,20 +501,25 @@ std::array convert_array_from_LVLH_to_bodyframe( const std::array input_LVLH_frame_array, const double input_roll, const double input_yaw, const double input_pitch); +Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, + const double height); +Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, + const double input_time); -Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, const double height); -Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, const double input_time); - -void sim_and_plot_gs_connectivity_distance_gnuplot(PhasedArrayGroundStation input_ground_station, - std::vector input_satellite_vector, - const SimParameters& input_sim_parameters, - const std::string file_name = "output"); +void sim_and_plot_gs_connectivity_distance_gnuplot( + PhasedArrayGroundStation input_ground_station, + std::vector input_satellite_vector, + const SimParameters& input_sim_parameters, + const std::string file_name = "output"); -void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_station, - std::vector input_satellite_vector, - const SimParameters& input_sim_parameters, - const std::string file_name = "output"); +void sim_and_plot_gs_connectivity_gnuplot( + PhasedArrayGroundStation input_ground_station, + std::vector input_satellite_vector, + const SimParameters& input_sim_parameters, + const std::string file_name = "output"); -int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double final_orbit_semimajor_axis_km, - const double thrust_magnitude, const double transfer_initiation_time = 0); +int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, + const double final_orbit_semimajor_axis_km, + const double thrust_magnitude, + const double transfer_initiation_time = 0); #endif \ No newline at end of file From 122bdf47c8035e4b07c9b74d69dea041ace7aa85 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 02:13:00 -0700 Subject: [PATCH 3/7] Running clang-format on src files --- src/PhasedArrayGroundStation.cpp | 252 ++++++++++--------- src/Satellite.cpp | 172 ++++++++----- src/utils.cpp | 419 ++++++++++++++++++------------- 3 files changed, 478 insertions(+), 365 deletions(-) diff --git a/src/PhasedArrayGroundStation.cpp b/src/PhasedArrayGroundStation.cpp index af24d28..9f1c7a0 100644 --- a/src/PhasedArrayGroundStation.cpp +++ b/src/PhasedArrayGroundStation.cpp @@ -1,139 +1,157 @@ +#include "PhasedArrayGroundStation.h" + +#include #include #include -#include -#include "PhasedArrayGroundStation.h" + #include "utils.h" using Eigen::Vector3d; void PhasedArrayGroundStation::generate_ECEF_position() { - ECEF_position_ = convert_lat_long_to_ECEF(latitude, longitude, height); + ECEF_position_ = convert_lat_long_to_ECEF(latitude, longitude, height); } Vector3d PhasedArrayGroundStation::get_ECI_position(double input_time) { - Vector3d ECI_position_vec = convert_ECEF_to_ECI(ECEF_position_, input_time); - return ECI_position_vec; - } - -double PhasedArrayGroundStation::distance_to_satellite(Satellite input_satellite) { - // Computes Euclidean distance to a satellite - std::array satellite_position_ECI = input_satellite.get_ECI_position(); - double current_time = input_satellite.get_instantaneous_time(); - Vector3d groundstation_position_ECI = get_ECI_position(current_time); - - // Convert to Eigen Vector3d - Vector3d satellite_position_vec; - for (size_t ind=0; ind satellite_position_ECI = input_satellite.get_ECI_position(); - // Convert to Eigen Vector3d - Vector3d satellite_position_vec; - for (size_t ind=0; ind satellite_position_ECI = + input_satellite.get_ECI_position(); + double current_time = input_satellite.get_instantaneous_time(); + Vector3d groundstation_position_ECI = get_ECI_position(current_time); + + // Convert to Eigen Vector3d + Vector3d satellite_position_vec; + for (size_t ind = 0; ind < satellite_position_ECI.size(); ind++) { + satellite_position_vec(ind) = satellite_position_ECI.at(ind); + } + // Order doesn't matter here + Vector3d difference_vec = + (satellite_position_vec - groundstation_position_ECI); + return difference_vec.norm(); +} - // Antenna plane normal is (given current assumptions) in the same - // direction as the vector from the center of the Earth to the ground station - Vector3d antenna_plane_normal_direction = groundstation_position_ECI; - antenna_plane_normal_direction.normalize(); +double PhasedArrayGroundStation::angle_to_satellite_from_normal( + Satellite input_satellite) { + // Computes angle between vector pointing from ground station to satellite + // and the vector normal to the ground station's antenna plane + // Note: for now, this antenna plane is assumed to be tangential to the Earth + // at the antenna's location. + + // Ref: https://archive.aoe.vt.edu/lutze/AOE4134/12SatelliteLookAngle.pdf + // but I don't think you need to use that topocentric-horizontal coordinate + // system to just get angle between antenna plane normal and station-satellite + // vector + double current_time = input_satellite.get_instantaneous_time(); + Vector3d groundstation_position_ECI = get_ECI_position(current_time); + + std::array satellite_position_ECI = + input_satellite.get_ECI_position(); + // Convert to Eigen Vector3d + Vector3d satellite_position_vec; + for (size_t ind = 0; ind < satellite_position_ECI.size(); ind++) { + satellite_position_vec(ind) = satellite_position_ECI.at(ind); + } - // See, e.g., https://www.wikihow.com/Find-the-Angle-Between-Two-Vectors - double angle_radians = acos(station_to_satellite_vec.dot(antenna_plane_normal_direction)); - // Make sure returned angle is in degrees - return (angle_radians * (180/M_PI)); + Vector3d station_to_satellite_vec = + satellite_position_vec - groundstation_position_ECI; + // Normalize to avoid needing magnitudes in angle calculation + // So this is just a unit vector now + station_to_satellite_vec.normalize(); + + // Antenna plane normal is (given current assumptions) in the same + // direction as the vector from the center of the Earth to the ground station + Vector3d antenna_plane_normal_direction = groundstation_position_ECI; + antenna_plane_normal_direction.normalize(); + + // See, e.g., https://www.wikihow.com/Find-the-Angle-Between-Two-Vectors + double angle_radians = + acos(station_to_satellite_vec.dot(antenna_plane_normal_direction)); + // Make sure returned angle is in degrees + return (angle_radians * (180 / M_PI)); } -int PhasedArrayGroundStation::num_sats_connected_at_this_time(double input_time) { - // Goal: check the number of satellites whose time ranges of being linked with this ground station - // include the current time - - // Method: two-pointer search along each element of linked_sats_list to find - // first and last ranges that overlap the input time - int connected_sats = 0; - - for (auto key_val_pair : linked_sats_map_) { - size_t satellite_ind = key_val_pair.first; - std::vector> satellite_comms_range_list = key_val_pair.second; - // For a given satellite - // I just need to identify whether there exists a single range that encompasses the input time - // I can do this by just finding the last range where the t_start <= input_time and - // see if t_end >= input_time - if (satellite_comms_range_list.size() == 1) { - if ((satellite_comms_range_list.at(0).first <= input_time) && (satellite_comms_range_list.at(0).second >= input_time)) { - connected_sats += 1; - continue; - } - } - int right_ind = satellite_comms_range_list.size() - 1; - int last_matching_pair_ind; - while (right_ind >= 0) { - std::pair right_range = satellite_comms_range_list.at(right_ind); - if (right_range.second < input_time) { - break; - } - if (right_range.first > input_time) { - right_ind -= 1; - } - else { - if (right_range.second >= input_time) { - connected_sats += 1; - } - break; - } +int PhasedArrayGroundStation::num_sats_connected_at_this_time( + double input_time) { + // Goal: check the number of satellites whose time ranges of being linked with + // this ground station include the current time + + // Method: two-pointer search along each element of linked_sats_list to find + // first and last ranges that overlap the input time + int connected_sats = 0; + + for (auto key_val_pair : linked_sats_map_) { + size_t satellite_ind = key_val_pair.first; + std::vector> satellite_comms_range_list = + key_val_pair.second; + // For a given satellite + // I just need to identify whether there exists a single range that + // encompasses the input time I can do this by just finding the last range + // where the t_start <= input_time and see if t_end >= input_time + if (satellite_comms_range_list.size() == 1) { + if ((satellite_comms_range_list.at(0).first <= input_time) && + (satellite_comms_range_list.at(0).second >= input_time)) { + connected_sats += 1; + continue; + } + } + int right_ind = satellite_comms_range_list.size() - 1; + int last_matching_pair_ind; + while (right_ind >= 0) { + std::pair right_range = + satellite_comms_range_list.at(right_ind); + if (right_range.second < input_time) { + break; + } + if (right_range.first > input_time) { + right_ind -= 1; + } else { + if (right_range.second >= input_time) { + connected_sats += 1; } + break; + } } - return connected_sats; + } + return connected_sats; } -void PhasedArrayGroundStation::update_linked_sats_map(const size_t satellite_index, const double connection_time, const double previous_time) { - // If you're just extending an existing range, update the t_end of existing pair, - // otherwise create a new pair with the current time as the t_start - if (linked_sats_map_.count(satellite_index) == 0) { - std::pair connection_time_range = {connection_time,connection_time}; - std::vector> tmp_vector = {connection_time_range}; - linked_sats_map_.emplace(satellite_index,tmp_vector); - } - else { - - // Look at most recently added range - std::vector> existing_connection_time_ranges = linked_sats_map_[satellite_index]; - std::pair most_recent_range = existing_connection_time_ranges.at(existing_connection_time_ranges.size() - 1); - if (most_recent_range.second == previous_time) { - // Just extending existing range - most_recent_range.second = connection_time; - existing_connection_time_ranges.at(existing_connection_time_ranges.size() - 1) = most_recent_range; - linked_sats_map_[satellite_index] = existing_connection_time_ranges; - } - else { - // New connection range - std::vector> existing_connection_time_ranges = linked_sats_map_[satellite_index]; - std::pair new_connection_time_range = {connection_time,connection_time}; - existing_connection_time_ranges.push_back(new_connection_time_range); - linked_sats_map_[satellite_index] = existing_connection_time_ranges; - } +void PhasedArrayGroundStation::update_linked_sats_map( + const size_t satellite_index, const double connection_time, + const double previous_time) { + // If you're just extending an existing range, update the t_end of existing + // pair, otherwise create a new pair with the current time as the t_start + if (linked_sats_map_.count(satellite_index) == 0) { + std::pair connection_time_range = {connection_time, + connection_time}; + std::vector> tmp_vector = {connection_time_range}; + linked_sats_map_.emplace(satellite_index, tmp_vector); + } else { + // Look at most recently added range + std::vector> existing_connection_time_ranges = + linked_sats_map_[satellite_index]; + std::pair most_recent_range = + existing_connection_time_ranges.at( + existing_connection_time_ranges.size() - 1); + if (most_recent_range.second == previous_time) { + // Just extending existing range + most_recent_range.second = connection_time; + existing_connection_time_ranges.at( + existing_connection_time_ranges.size() - 1) = most_recent_range; + linked_sats_map_[satellite_index] = existing_connection_time_ranges; + } else { + // New connection range + std::vector> existing_connection_time_ranges = + linked_sats_map_[satellite_index]; + std::pair new_connection_time_range = {connection_time, + connection_time}; + existing_connection_time_ranges.push_back(new_connection_time_range); + linked_sats_map_[satellite_index] = existing_connection_time_ranges; } + } } diff --git a/src/Satellite.cpp b/src/Satellite.cpp index 6aeebb0..174b75e 100644 --- a/src/Satellite.cpp +++ b/src/Satellite.cpp @@ -46,9 +46,10 @@ std::array Satellite::calculate_perifocal_velocity() { std::array calculated_perifocal_velocity; double p = a_ * (1 - eccentricity_) * (1 + eccentricity_); // rearranging eq. 1-47 - const double mu_Earth = G*mass_Earth; + const double mu_Earth = G * mass_Earth; double v_perifocal_P = sqrt(mu_Earth / p) * (-sin(true_anomaly_)); - double v_perifocal_Q = sqrt(mu_Earth / p) * (eccentricity_ + cos(true_anomaly_)); + double v_perifocal_Q = + sqrt(mu_Earth / p) * (eccentricity_ + cos(true_anomaly_)); calculated_perifocal_velocity.at(0) = v_perifocal_P; calculated_perifocal_velocity.at(1) = v_perifocal_Q; @@ -175,9 +176,11 @@ std::array Satellite::convert_ECI_to_perifocal( // // populate list of thrust forces at half a timestep past, for RK4 // // calculations -// std::vector> list_of_LVLH_forces_at_half_timestep_past = +// std::vector> +// list_of_LVLH_forces_at_half_timestep_past = // {}; -// std::vector> list_of_ECI_forces_at_half_timestep_past = +// std::vector> list_of_ECI_forces_at_half_timestep_past +// = // {}; // for (const ThrustProfileLVLH thrust_profile : thrust_profile_list_) { @@ -192,9 +195,11 @@ std::array Satellite::convert_ECI_to_perifocal( // } // // populate list of thrust forces at a timestep past, for RK4 calculations -// std::vector> list_of_LVLH_forces_at_one_timestep_past = +// std::vector> list_of_LVLH_forces_at_one_timestep_past +// = // {}; -// std::vector> list_of_ECI_forces_at_one_timestep_past = +// std::vector> list_of_ECI_forces_at_one_timestep_past +// = // {}; // for (const ThrustProfileLVLH thrust_profile : thrust_profile_list_) { @@ -209,16 +214,19 @@ std::array Satellite::convert_ECI_to_perifocal( // } // std::array output_combined_position_and_velocity_array = -// RK4_step<6>(combined_initial_position_and_velocity_array, input_step_size, +// RK4_step<6>(combined_initial_position_and_velocity_array, +// input_step_size, // RK4_deriv_function_orbit_position_and_velocity, m_, // list_of_ECI_forces_at_this_time_, // list_of_ECI_forces_at_half_timestep_past, // list_of_ECI_forces_at_one_timestep_past); // // std::array output_combined_angular_array= -// // RK4_step<6>(combined_initial_angular_array,input_step_size,RK4_deriv_function_angular,I_,list_of_body_frame_torques_at_this_time_,list_of_body_frame_torques_at_half_timestep_past,list_of_body_frame_torques_at_one_timestep_past); +// // +// RK4_step<6>(combined_initial_angular_array,input_step_size,RK4_deriv_function_angular,I_,list_of_body_frame_torques_at_this_time_,list_of_body_frame_torques_at_half_timestep_past,list_of_body_frame_torques_at_one_timestep_past); // for (size_t ind = 0; ind < 3; ind++) { -// ECI_position_.at(ind) = output_combined_position_and_velocity_array.at(ind); +// ECI_position_.at(ind) = +// output_combined_position_and_velocity_array.at(ind); // ECI_velocity_.at(ind) = // output_combined_position_and_velocity_array.at(ind + 3); // // also update the perifocal versions @@ -227,8 +235,9 @@ std::array Satellite::convert_ECI_to_perifocal( // } // t_ += input_step_size; -// list_of_LVLH_forces_at_this_time_ = list_of_LVLH_forces_at_one_timestep_past; -// list_of_ECI_forces_at_this_time_ = list_of_ECI_forces_at_one_timestep_past; +// list_of_LVLH_forces_at_this_time_ = +// list_of_LVLH_forces_at_one_timestep_past; list_of_ECI_forces_at_this_time_ +// = list_of_ECI_forces_at_one_timestep_past; // // Update orbital parameters // update_orbital_elements_from_position_and_velocity(); @@ -276,13 +285,15 @@ void Satellite::add_LVLH_thrust_profile( } } - // Now the version for argument of periapsis change maneuvers - void Satellite::add_LVLH_thrust_profile(const double input_thrust_start_time, const double final_arg_of_periapsis, - const double input_thrust_magnitude) { - ThrustProfileLVLH thrust_profile(input_thrust_start_time,final_arg_of_periapsis,input_thrust_magnitude, - arg_of_periapsis_, eccentricity_, a_, m_); - thrust_profile_list_.push_back(thrust_profile); - } +// Now the version for argument of periapsis change maneuvers +void Satellite::add_LVLH_thrust_profile(const double input_thrust_start_time, + const double final_arg_of_periapsis, + const double input_thrust_magnitude) { + ThrustProfileLVLH thrust_profile( + input_thrust_start_time, final_arg_of_periapsis, input_thrust_magnitude, + arg_of_periapsis_, eccentricity_, a_, m_); + thrust_profile_list_.push_back(thrust_profile); +} int Satellite::update_orbital_elements_from_position_and_velocity() { // Anytime the orbit is changed via external forces, need to update the @@ -290,7 +301,7 @@ int Satellite::update_orbital_elements_from_position_and_velocity() { // even in absence of external forces Using approach from Fundamentals of // Astrodynamics int error_code = 0; // 0 represents nominal operation - double mu_Earth = G*mass_Earth; + double mu_Earth = G * mass_Earth; Vector3d position_vector = {ECI_position_.at(0), ECI_position_.at(1), ECI_position_.at(2)}; Vector3d velocity_vector = {ECI_velocity_.at(0), ECI_velocity_.at(1), @@ -305,10 +316,11 @@ int Satellite::update_orbital_elements_from_position_and_velocity() { double r_magnitude = get_radius(); Vector3d e_vec_component_1 = - (1.0 / mu_Earth) * (v_magnitude * v_magnitude - (mu_Earth / r_magnitude)) * - position_vector; - Vector3d e_vec_component_2 = - (1.0 / mu_Earth) * (position_vector.dot(velocity_vector)) * velocity_vector; + (1.0 / mu_Earth) * + (v_magnitude * v_magnitude - (mu_Earth / r_magnitude)) * position_vector; + Vector3d e_vec_component_2 = (1.0 / mu_Earth) * + (position_vector.dot(velocity_vector)) * + velocity_vector; Vector3d e_vec = e_vec_component_1 - e_vec_component_2; double calculated_eccentricity = e_vec.norm(); @@ -331,13 +343,13 @@ int Satellite::update_orbital_elements_from_position_and_velocity() { calculated_arg_of_periapsis = 2 * M_PI - calculated_arg_of_periapsis; } calculated_true_anomaly = acos(e_vec.dot(position_vector) / - (calculated_eccentricity * r_magnitude)); + (calculated_eccentricity * r_magnitude)); if (std::isnan(calculated_true_anomaly)) { // First try arg of the following acos call to a float to avoid bug - // where it ended up being represented by a value with magnitude + // where it ended up being represented by a value with magnitude // slightly larger than one, causing NaN in output of acos - float true_anomaly_acos_arg_float = e_vec.dot(position_vector) / - (calculated_eccentricity * r_magnitude); + float true_anomaly_acos_arg_float = + e_vec.dot(position_vector) / (calculated_eccentricity * r_magnitude); calculated_true_anomaly = acos(true_anomaly_acos_arg_float); if (std::isnan(calculated_true_anomaly)) { std::cout << "NaN true anomaly encountered.\n"; @@ -395,7 +407,8 @@ std::pair Satellite::evolve_RK45( const double input_epsilon, const double input_step_size, const bool perturbation, const bool atmospheric_drag, const std::pair drag_elements) { - // std::cout << "In EvolveRK45, received perturbation bool: " << perturbation << "\n"; + // std::cout << "In EvolveRK45, received perturbation bool: " << perturbation + // << "\n"; // perturbation is a flag which, when set to true, currently accounts for J2 // perturbation. @@ -413,11 +426,12 @@ std::pair Satellite::evolve_RK45( // F_10 is the first element, A_p is the second element double input_F_10 = drag_elements.first; double input_A_p = drag_elements.second; - - // Initialize arg of periapsis change thrust profile from current orbital parameters, - // if there is one that hasn't already been initialized + + // Initialize arg of periapsis change thrust profile from current orbital + // parameters, if there is one that hasn't already been initialized check_for_maneuvers_to_initialize(); - // Add any thrusts from an argument of periapsis change maneuver, if applicable + // Add any thrusts from an argument of periapsis change maneuver, if + // applicable int arg_of_periapsis_code = add_arg_of_periapsis_change_thrust(); std::array @@ -522,14 +536,15 @@ std::pair Satellite::evolve_RK45( std::pair evolve_RK45_output_pair; // Orbital radius shouldn't be less than or equal to Earth's radius double new_orbital_radius = get_radius(); - if (new_orbital_radius <= radius_Earth){ + if (new_orbital_radius <= radius_Earth) { orbit_elems_error_code = 2; } evolve_RK45_output_pair.first = new_step_size; evolve_RK45_output_pair.second = orbit_elems_error_code; - // If you just added a temporally localized thrust profile stemming from an argument of periapsis change thrust profile, - // remove it now that it's no longer needed to avoid bloat of the thrust profile list + // If you just added a temporally localized thrust profile stemming from an + // argument of periapsis change thrust profile, remove it now that it's no + // longer needed to avoid bloat of the thrust profile list if (arg_of_periapsis_code == 1) { thrust_profile_list_.pop_back(); } @@ -537,19 +552,20 @@ std::pair Satellite::evolve_RK45( } // Returns a specific orbital element -double Satellite::get_orbital_parameter(const std::string orbital_parameter_name) { +double Satellite::get_orbital_parameter( + const std::string orbital_parameter_name) { if (orbital_parameter_name == "Semimajor Axis") { return a_; } else if (orbital_parameter_name == "Eccentricity") { return eccentricity_; } else if (orbital_parameter_name == "Inclination") { - return inclination_*(180/M_PI); // Returns val in degrees + return inclination_ * (180 / M_PI); // Returns val in degrees } else if (orbital_parameter_name == "RAAN") { - return raan_ * (180.0 / M_PI); // Returns val in degrees + return raan_ * (180.0 / M_PI); // Returns val in degrees } else if (orbital_parameter_name == "Argument of Periapsis") { - return arg_of_periapsis_ * (180.0 / M_PI); // Returns val in degrees + return arg_of_periapsis_ * (180.0 / M_PI); // Returns val in degrees } else if (orbital_parameter_name == "True Anomaly") { - return true_anomaly_ * (180.0 / M_PI); // Returns val in degrees + return true_anomaly_ * (180.0 / M_PI); // Returns val in degrees } else if (orbital_parameter_name == "Orbital Rate") { return orbital_rate_; } else if (orbital_parameter_name == "Orbital Angular Acceleration") { @@ -655,17 +671,20 @@ void Satellite::initialize_and_normalize_body_quaternion( // Return a specific attitude-related value double Satellite::get_attitude_val(std::string input_attitude_val_name) { if (input_attitude_val_name == "Roll") { - return roll_angle_ * (180.0 / M_PI); // Returns val in degrees + return roll_angle_ * (180.0 / M_PI); // Returns val in degrees } else if (input_attitude_val_name == "Pitch") { - return pitch_angle_ * (180.0 / M_PI); // Returns val in degrees + return pitch_angle_ * (180.0 / M_PI); // Returns val in degrees } else if (input_attitude_val_name == "Yaw") { - return yaw_angle_ * (180.0 / M_PI); // Returns val in degrees + return yaw_angle_ * (180.0 / M_PI); // Returns val in degrees } else if (input_attitude_val_name == "omega_x") { - return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(0) * (180.0 / M_PI); // Returns val in degrees/s + return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(0) * + (180.0 / M_PI); // Returns val in degrees/s } else if (input_attitude_val_name == "omega_y") { - return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(1) * (180.0 / M_PI); // Returns val in degrees/s + return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(1) * + (180.0 / M_PI); // Returns val in degrees/s } else if (input_attitude_val_name == "omega_z") { - return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(2) * (180.0 / M_PI); // Returns val in degrees/s + return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(2) * + (180.0 / M_PI); // Returns val in degrees/s } else if (input_attitude_val_name == "q_0") { return quaternion_satellite_bodyframe_wrt_LVLH_.at(0); } else if (input_attitude_val_name == "q_1") { @@ -690,40 +709,59 @@ void Satellite::initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame() { } int Satellite::add_arg_of_periapsis_change_thrust() { // Returning 0 means didn't find any arg of periapsis change thrust profiles - // Returning 1 means it did find one and added a temporally localized thrust at this time + // Returning 1 means it did find one and added a temporally localized thrust + // at this time for (ThrustProfileLVLH thrust_profile : thrust_profile_list_) { - if ((thrust_profile.arg_of_periapsis_change_thrust_profile) && (thrust_profile.t_start_ <= t_) && (thrust_profile.t_end_ >= t_)) { - std::array thrust_direction_vec = {sin(true_anomaly_), 0, cos(true_anomaly_)}; - - add_LVLH_thrust_profile(thrust_direction_vec, thrust_profile.sign_of_delta_omega*thrust_profile.thrust_magnitude_,t_,thrust_profile.t_end_); - // can add one with t_end stretching all the way to the t_end of the total arg of periapsis change maneuver because this temporary thrust profile will - // be deleted after this RK45 step. This end time is given so that whatever timestep is chosen for this step, all intermediate calculated steps will - // also see this thrust. + if ((thrust_profile.arg_of_periapsis_change_thrust_profile) && + (thrust_profile.t_start_ <= t_) && (thrust_profile.t_end_ >= t_)) { + std::array thrust_direction_vec = {sin(true_anomaly_), 0, + cos(true_anomaly_)}; + + add_LVLH_thrust_profile( + thrust_direction_vec, + thrust_profile.sign_of_delta_omega * thrust_profile.thrust_magnitude_, + t_, thrust_profile.t_end_); + // can add one with t_end stretching all the way to the t_end of the total + // arg of periapsis change maneuver because this temporary thrust profile + // will be deleted after this RK45 step. This end time is given so that + // whatever timestep is chosen for this step, all intermediate calculated + // steps will also see this thrust. return 1; } } return 0; } void Satellite::check_for_maneuvers_to_initialize() { - for (size_t maneuver_index = 0; maneuver_index < maneuvers_awaiting_initiation_.size(); maneuver_index++) { - std::pair> maneuver_info = maneuvers_awaiting_initiation_.at(maneuver_index); + for (size_t maneuver_index = 0; + maneuver_index < maneuvers_awaiting_initiation_.size(); + maneuver_index++) { + std::pair> maneuver_info = + maneuvers_awaiting_initiation_.at(maneuver_index); const double maneuver_start_time = maneuver_info.second.at(0); - if ((maneuver_start_time <= t_) && (maneuver_info.first == "Argument of Periapsis Change")) { + if ((maneuver_start_time <= t_) && + (maneuver_info.first == "Argument of Periapsis Change")) { // Need to initialize this maneuver const double target_arg_of_periapsis_deg = maneuver_info.second.at(1); - const double target_arg_of_periapsis_rad = target_arg_of_periapsis_deg * (M_PI/180.0); + const double target_arg_of_periapsis_rad = + target_arg_of_periapsis_deg * (M_PI / 180.0); const double thrust_magnitude = maneuver_info.second.at(2); - ThrustProfileLVLH thrust_profile(maneuver_start_time,target_arg_of_periapsis_rad,thrust_magnitude, - arg_of_periapsis_, eccentricity_, a_, m_); + ThrustProfileLVLH thrust_profile( + maneuver_start_time, target_arg_of_periapsis_rad, thrust_magnitude, + arg_of_periapsis_, eccentricity_, a_, m_); thrust_profile_list_.push_back(thrust_profile); - maneuvers_awaiting_initiation_.erase(maneuvers_awaiting_initiation_.begin() + maneuver_index); + maneuvers_awaiting_initiation_.erase( + maneuvers_awaiting_initiation_.begin() + maneuver_index); } } } -void Satellite::add_maneuver(const std::string maneuver_type, const double maneuver_start_time, - const double final_parameter_val, const double thrust_magnitude) { - std::array maneuver_vals = {maneuver_start_time,final_parameter_val,thrust_magnitude}; - std::pair> maneuver_info = {maneuver_type,maneuver_vals}; - maneuvers_awaiting_initiation_.push_back(maneuver_info); - } \ No newline at end of file +void Satellite::add_maneuver(const std::string maneuver_type, + const double maneuver_start_time, + const double final_parameter_val, + const double thrust_magnitude) { + std::array maneuver_vals = {maneuver_start_time, + final_parameter_val, thrust_magnitude}; + std::pair> maneuver_info = {maneuver_type, + maneuver_vals}; + maneuvers_awaiting_initiation_.push_back(maneuver_info); +} \ No newline at end of file diff --git a/src/utils.cpp b/src/utils.cpp index 9809c7a..062299f 100644 --- a/src/utils.cpp +++ b/src/utils.cpp @@ -1,11 +1,12 @@ +#include "utils.h" + #include #include #include #include -#include "Satellite.h" #include "PhasedArrayGroundStation.h" -#include "utils.h" +#include "Satellite.h" using Eigen::Matrix3d; using Eigen::Matrix4d; @@ -87,8 +88,8 @@ std::array convert_LVLH_to_ECI_manual( // baselining cartesian coordinates in ECI frame // std::array calculate_orbital_acceleration( -// const std::array input_r_vec, const double input_spacecraft_mass, -// const std::vector> +// const std::array input_r_vec, const double +// input_spacecraft_mass, const std::vector> // input_vec_of_force_vectors_in_ECI) { // // Note: this is the version used in the RK4 solver // // orbital acceleration = -G m_Earth/distance^3 * r_vec (just based on @@ -96,15 +97,18 @@ std::array convert_LVLH_to_ECI_manual( // // between satellite and Earth // // https://en.wikipedia.org/wiki/Newton%27s_law_of_universal_gravitation) // // going to be assuming Earth's position doesn't change for now -// // also assuming Earth is spherical, can loosen this assumption in the future +// // also assuming Earth is spherical, can loosen this assumption in the +// future // // note: this is in ECI frame // std::array acceleration_vec_due_to_gravity = -// input_r_vec; // shouldn't need to explicitly call copy function because +// input_r_vec; // shouldn't need to explicitly call copy function +// because // // input_r_vec is passed by value not ref // // F=ma -// // a=F/m = (F_grav + F_ext)/m = (F_grav/m) + (F_ext/m) = -G*M_Earth/distance^3 +// // a=F/m = (F_grav + F_ext)/m = (F_grav/m) + (F_ext/m) = +// -G*M_Earth/distance^3 // // + ... // const double distance = sqrt(input_r_vec.at(0) * input_r_vec.at(0) + @@ -227,9 +231,9 @@ std::array calculate_orbital_acceleration( // perturbation Ref: // https://vatankhahghadim.github.io/AER506/Notes/6%20-%20Orbital%20Perturbations.pdf double J2 = 1.083 * pow(10, -3); - const double mu_Earth = G*mass_Earth; - double C = - 3 * mu_Earth * J2 * radius_Earth * radius_Earth / (2 * pow(distance, 4)); + const double mu_Earth = G * mass_Earth; + double C = 3 * mu_Earth * J2 * radius_Earth * radius_Earth / + (2 * pow(distance, 4)); double x = input_r_vec.at(0); double y = input_r_vec.at(1); double rho = sqrt(pow(x, 2) + pow(y, 2)); @@ -283,10 +287,10 @@ std::array calculate_orbital_acceleration( double a5 = 1.904383 * pow(10, -8); double a6 = -7.189421 * pow(10, -11); double a7 = 1.060067 * pow(10, -13); - double fit_val = a0 + a1*altitude + a2*pow(altitude,2) - + a3*pow(altitude,3) + a4*pow(altitude,4) - + a5*pow(altitude,5) + a6*pow(altitude,6) - + a7*pow(altitude,7); + double fit_val = a0 + a1 * altitude + a2 * pow(altitude, 2) + + a3 * pow(altitude, 3) + a4 * pow(altitude, 4) + + a5 * pow(altitude, 5) + a6 * pow(altitude, 6) + + a7 * pow(altitude, 7); rho = pow(10, fit_val); } else { @@ -338,7 +342,8 @@ std::array calculate_orbital_acceleration( // input_vec_of_force_vectors_in_ECI); // for (size_t ind = 3; ind < 6; ind++) { -// derivative_of_input_y.at(ind) = calculated_orbital_acceleration.at(ind - 3); +// derivative_of_input_y.at(ind) = calculated_orbital_acceleration.at(ind - +// 3); // } // return derivative_of_input_y; @@ -353,7 +358,8 @@ std::array RK45_deriv_function_orbit_position_and_velocity( const double input_F_10, const double input_A_p, const double input_A_s, const double input_satellite_mass, const bool perturbation, const bool atmospheric_drag) { - // std::cout << "In RK45 deriv function orbit position and velocity, received perturbation bool: " << perturbation << "\n"; + // std::cout << "In RK45 deriv function orbit position and velocity, received + // perturbation bool: " << perturbation << "\n"; std::array derivative_of_input_y = {}; std::array position_array = {}; std::array velocity_array = {}; @@ -390,16 +396,18 @@ void sim_and_draw_orbit_gnuplot(std::vector input_satellite_vector, } // first, open "pipe" to gnuplot std::string gnuplot_arg_string = "gnuplot"; - if (input_sim_parameters.terminal_name_3D == "qt"){ + if (input_sim_parameters.terminal_name_3D == "qt") { gnuplot_arg_string += " -persist"; } - FILE *gnuplot_pipe = popen(gnuplot_arg_string.c_str(), "w"); + FILE* gnuplot_pipe = popen(gnuplot_arg_string.c_str(), "w"); // if it exists if (gnuplot_pipe) { - fprintf(gnuplot_pipe, "set terminal '%s' size 900,700 font ',14'\n",input_sim_parameters.terminal_name_3D.c_str()); + fprintf(gnuplot_pipe, "set terminal '%s' size 900,700 font ',14'\n", + input_sim_parameters.terminal_name_3D.c_str()); if (input_sim_parameters.terminal_name_3D == "png") { - fprintf(gnuplot_pipe, "set output '../%s.png'\n",output_file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", + output_file_name.c_str()); } // formatting fprintf(gnuplot_pipe, "set xlabel 'x [m]' offset 0,-2\n"); @@ -411,19 +419,19 @@ void sim_and_draw_orbit_gnuplot(std::vector input_satellite_vector, // fprintf(gnuplot_pipe,"set view 70,1,1,1\n"); fprintf(gnuplot_pipe, "set view equal xyz\n"); if (input_sim_parameters.x_increment != 0) { - fprintf(gnuplot_pipe, "set xtics %e offset 0,-1\n",input_sim_parameters.x_increment); - } - else { + fprintf(gnuplot_pipe, "set xtics %e offset 0,-1\n", + input_sim_parameters.x_increment); + } else { fprintf(gnuplot_pipe, "set xtics offset 0,-1\n"); } if (input_sim_parameters.y_increment != 0) { - fprintf(gnuplot_pipe, "set ytics %e offset -1,0\n",input_sim_parameters.y_increment); - } - else { + fprintf(gnuplot_pipe, "set ytics %e offset -1,0\n", + input_sim_parameters.y_increment); + } else { fprintf(gnuplot_pipe, "set ytics offset -1,0\n"); } if (input_sim_parameters.z_increment != 0) { - fprintf(gnuplot_pipe, "set ztics %e\n",input_sim_parameters.z_increment); + fprintf(gnuplot_pipe, "set ztics %e\n", input_sim_parameters.z_increment); } fprintf(gnuplot_pipe, "unset colorbox\n"); fprintf(gnuplot_pipe, "set style fill transparent solid 1.0\n"); @@ -514,15 +522,18 @@ void sim_and_draw_orbit_gnuplot(std::vector input_satellite_vector, double current_satellite_time = current_satellite.get_instantaneous_time(); while (current_satellite_time < input_sim_parameters.total_sim_time) { - std::pair drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + std::pair drag_elements = {input_sim_parameters.F_10, + input_sim_parameters.A_p}; std::pair new_timestep_and_error_code = - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - input_sim_parameters.perturbation_bool, - input_sim_parameters.drag_bool, drag_elements); + current_satellite.evolve_RK45( + input_sim_parameters.epsilon, timestep_to_use, + input_sim_parameters.perturbation_bool, + input_sim_parameters.drag_bool, drag_elements); double new_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; if (error_code != 0) { - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code + << " detected, halting visualization\n"; fprintf(gnuplot_pipe, "e\n"); fprintf(gnuplot_pipe, "exit \n"); pclose(gnuplot_pipe); @@ -537,7 +548,7 @@ void sim_and_draw_orbit_gnuplot(std::vector input_satellite_vector, fprintf(gnuplot_pipe, "e\n"); } - if (input_sim_parameters.terminal_name_3D == "qt"){ + if (input_sim_parameters.terminal_name_3D == "qt") { fprintf(gnuplot_pipe, "pause mouse keypress\n"); } fprintf(gnuplot_pipe, "exit \n"); @@ -554,22 +565,22 @@ void sim_and_draw_orbit_gnuplot(std::vector input_satellite_vector, // Objective: simulate the input satellites over the specified total sim time, // and plot a specific orbital element over time void sim_and_plot_orbital_elem_gnuplot( - std::vector input_satellite_vector, - const SimParameters& input_sim_parameters, - std::string input_orbital_element_name, - const std::string file_name) { + std::vector input_satellite_vector, + const SimParameters& input_sim_parameters, + std::string input_orbital_element_name, const std::string file_name) { if (input_satellite_vector.size() < 1) { std::cout << "No input Satellite objects\n"; return; } // first, open "pipe" to gnuplot - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); // if it exists if (gnuplot_pipe) { - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, + "set terminal png size 800,500 font ',14' linewidth 2\n"); // formatting - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); if (input_orbital_element_name == "Semimajor Axis") { fprintf(gnuplot_pipe, "set ylabel '%s [m]'\n", @@ -582,7 +593,8 @@ void sim_and_plot_orbital_elem_gnuplot( input_orbital_element_name.c_str()); } fprintf(gnuplot_pipe, "set title '%s simulated up to time %.2f s'\n", - input_orbital_element_name.c_str(), input_sim_parameters.total_sim_time); + input_orbital_element_name.c_str(), + input_sim_parameters.total_sim_time); fprintf(gnuplot_pipe, "set key right bottom\n"); // plotting @@ -662,18 +674,23 @@ void sim_and_plot_orbital_elem_gnuplot( double timestep_to_use = input_sim_parameters.initial_timestep_guess; current_satellite_time = current_satellite.get_instantaneous_time(); while (current_satellite_time < input_sim_parameters.total_sim_time) { - // std::cout << "========================================================\n"; - // std::cout << "Running an evolve step at satellite time " << current_satellite_time << "\n"; - std::pair drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + // std::cout << + // "========================================================\n"; + // std::cout << "Running an evolve step at satellite time " << + // current_satellite_time << "\n"; + std::pair drag_elements = {input_sim_parameters.F_10, + input_sim_parameters.A_p}; std::pair new_timestep_and_error_code = - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - input_sim_parameters.perturbation_bool, - input_sim_parameters.drag_bool, drag_elements); + current_satellite.evolve_RK45( + input_sim_parameters.epsilon, timestep_to_use, + input_sim_parameters.perturbation_bool, + input_sim_parameters.drag_bool, drag_elements); double new_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; if (error_code != 0) { - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code + << " detected, halting visualization\n"; fprintf(gnuplot_pipe, "e\n"); fprintf(gnuplot_pipe, "exit \n"); pclose(gnuplot_pipe); @@ -705,9 +722,8 @@ void sim_and_plot_orbital_elem_gnuplot( Matrix3d z_rot_matrix(const double input_angle) { Matrix3d z_rotation_matrix; - z_rotation_matrix << cos(input_angle), -sin(input_angle), 0, - sin(input_angle),cos(input_angle), 0, - 0, 0, 1; + z_rotation_matrix << cos(input_angle), -sin(input_angle), 0, sin(input_angle), + cos(input_angle), 0, 0, 0, 1; return z_rotation_matrix; } @@ -728,26 +744,25 @@ Matrix3d x_rot_matrix(const double input_angle) { return x_rotation_matrix; } - // Objective: simulate the input satellites over the specified total sim time, // and plot a specific attitude-related value over time void sim_and_plot_attitude_evolution_gnuplot( - std::vector input_satellite_vector, + std::vector input_satellite_vector, const SimParameters& input_sim_parameters, - const std::string input_plotted_val_name, - const std::string file_name) { + const std::string input_plotted_val_name, const std::string file_name) { if (input_satellite_vector.size() < 1) { std::cout << "No input Satellite objects\n"; return; } // first, open "pipe" to gnuplot - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); // if it exists if (gnuplot_pipe) { - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, + "set terminal png size 800,500 font ',14' linewidth 2\n"); // formatting - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); if ((input_plotted_val_name == "omega_x") || (input_plotted_val_name == "omega_y") || @@ -764,7 +779,8 @@ void sim_and_plot_attitude_evolution_gnuplot( input_plotted_val_name.c_str()); } fprintf(gnuplot_pipe, "set title '%s simulated up to time %.2f s'\n", - input_plotted_val_name.c_str(), input_sim_parameters.total_sim_time); + input_plotted_val_name.c_str(), + input_sim_parameters.total_sim_time); fprintf(gnuplot_pipe, "set key right bottom\n"); // plotting @@ -843,16 +859,19 @@ void sim_and_plot_attitude_evolution_gnuplot( double timestep_to_use = input_sim_parameters.initial_timestep_guess; current_satellite_time = current_satellite.get_instantaneous_time(); while (current_satellite_time < input_sim_parameters.total_sim_time) { - std::pair drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + std::pair drag_elements = {input_sim_parameters.F_10, + input_sim_parameters.A_p}; std::pair new_timestep_and_error_code = - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - input_sim_parameters.perturbation_bool, - input_sim_parameters.drag_bool, drag_elements); + current_satellite.evolve_RK45( + input_sim_parameters.epsilon, timestep_to_use, + input_sim_parameters.perturbation_bool, + input_sim_parameters.drag_bool, drag_elements); double new_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; if (error_code != 0) { - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code + << " detected, halting visualization\n"; fprintf(gnuplot_pipe, "e\n"); fprintf(gnuplot_pipe, "exit \n"); pclose(gnuplot_pipe); @@ -873,7 +892,6 @@ void sim_and_plot_attitude_evolution_gnuplot( pclose(gnuplot_pipe); std::cout << "Done\n"; - } else { std::cout << "gnuplot not found"; } @@ -1213,46 +1231,46 @@ std::array convert_array_from_LVLH_to_bodyframe( return bodyframe_arr; } +Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, + const double height) { + double a = 6378137; // Equatorial radius [m] + double b = 6356752; // Polar radius [m] - -Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, const double height) { - double a = 6378137; // Equatorial radius [m] - double b = 6356752; // Polar radius [m] - - // Refs: https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#From_geodetic_to_ECEF_coordinates + // Refs: + // https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#From_geodetic_to_ECEF_coordinates // https://nssdc.gsfc.nasa.gov/planetary/factsheet/earthfact.html - double e = 1 - ((b * b)/(a * a)); - double N = a / (sqrt(1 - ((e * e) / (1 + pow(cos(latitude)/sin(latitude),2)) ))); - double x = (N + height)*cos(latitude)*cos(longitude); - double y = (N + height)*cos(latitude)*sin(longitude); - double z = ((1 - e * e)*N + height) * sin(latitude); - Vector3d output_ECEF_array = {x,y,z}; + double e = 1 - ((b * b) / (a * a)); + double N = + a / (sqrt(1 - ((e * e) / (1 + pow(cos(latitude) / sin(latitude), 2))))); + double x = (N + height) * cos(latitude) * cos(longitude); + double y = (N + height) * cos(latitude) * sin(longitude); + double z = ((1 - e * e) * N + height) * sin(latitude); + Vector3d output_ECEF_array = {x, y, z}; return output_ECEF_array; } -Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, const double input_time) { - // Simple rotation-based conversion, not yet accounting for higher-fidelity effects like changes to Earth axes - // Ref: https://x-lumin.com/wp-content/uploads/2020/09/Coordinate_Transforms.pdf +Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, + const double input_time) { + // Simple rotation-based conversion, not yet accounting for higher-fidelity + // effects like changes to Earth axes Ref: + // https://x-lumin.com/wp-content/uploads/2020/09/Coordinate_Transforms.pdf // https://space.stackexchange.com/questions/43187/is-this-commonly-attributed-eci-earth-centered-inertial-to-ecef-earth-centere // https://space.stackexchange.com/questions/38807/transform-eci-to-ecef - double omega_Earth = 0.261799387799149 * (1.0/3600.0); // [radians / second] - double ERA_at_J200 = 280.46 * (M_PI/180); //radians - // Going to be assuming, for simplicity, that satellites start orbiting at the J200 epoch - double theta_g = ERA_at_J200 + omega_Earth*input_time; + double omega_Earth = + 0.261799387799149 * (1.0 / 3600.0); // [radians / second] + double ERA_at_J200 = 280.46 * (M_PI / 180); // radians + // Going to be assuming, for simplicity, that satellites start orbiting at the + // J200 epoch + double theta_g = ERA_at_J200 + omega_Earth * input_time; Matrix3d rotation_matrix = z_rot_matrix(theta_g); - Vector3d ECI_array = rotation_matrix*input_ECEF_position; + Vector3d ECI_array = rotation_matrix * input_ECEF_position; return ECI_array; } - - - void sim_and_plot_gs_connectivity_distance_gnuplot( - PhasedArrayGroundStation input_ground_station, - std::vector input_satellite_vector, - const SimParameters& input_sim_parameters, - const std::string file_name) { - + PhasedArrayGroundStation input_ground_station, + std::vector input_satellite_vector, + const SimParameters& input_sim_parameters, const std::string file_name) { // Objective: given an input ground station and satellite vector, // plot contact distances between ground station and satellites over time @@ -1262,20 +1280,24 @@ void sim_and_plot_gs_connectivity_distance_gnuplot( } // first, open "pipe" to gnuplot - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); // if it exists if (gnuplot_pipe) { - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, + "set terminal png size 800,500 font ',14' linewidth 2\n"); // formatting - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); fprintf(gnuplot_pipe, "set ylabel 'Distance [m]'\n"); - fprintf(gnuplot_pipe, "set title 'Phased array ground station connectivity " - "with %d beams'\n",input_ground_station.num_beams_); + fprintf(gnuplot_pipe, + "set title 'Phased array ground station connectivity " + "with %d beams'\n", + input_ground_station.num_beams_); fprintf(gnuplot_pipe, "set key outside\n"); - int x_max_plot_window = std::floor(input_sim_parameters.total_sim_time*1.05); - fprintf(gnuplot_pipe, "set xrange[0:%d]\n",x_max_plot_window); + int x_max_plot_window = + std::floor(input_sim_parameters.total_sim_time * 1.05); + fprintf(gnuplot_pipe, "set xrange[0:%d]\n", x_max_plot_window); // plotting // first satellite @@ -1345,50 +1367,66 @@ void sim_and_plot_gs_connectivity_distance_gnuplot( double current_satellite_time = current_satellite.get_instantaneous_time(); double previous_time = current_satellite_time - 1; - double ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + double ground_station_beam_angle = + input_ground_station.angle_to_satellite_from_normal( + current_satellite); double initial_distance; - if (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) { + if (ground_station_beam_angle > + input_ground_station.max_beam_angle_from_normal_) { fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); + } else { + initial_distance = + input_ground_station.distance_to_satellite(current_satellite); + fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, + initial_distance); } - else { - initial_distance = input_ground_station.distance_to_satellite(current_satellite); - fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, initial_distance); - } - + double evolved_distance = {0}; double timestep_to_use = input_sim_parameters.initial_timestep_guess; current_satellite_time = current_satellite.get_instantaneous_time(); while (current_satellite_time < input_sim_parameters.total_sim_time) { - std::pair drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + std::pair drag_elements = {input_sim_parameters.F_10, + input_sim_parameters.A_p}; std::pair new_timestep_and_error_code = - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - input_sim_parameters.perturbation_bool, - input_sim_parameters.drag_bool, drag_elements); + current_satellite.evolve_RK45( + input_sim_parameters.epsilon, timestep_to_use, + input_sim_parameters.perturbation_bool, + input_sim_parameters.drag_bool, drag_elements); double new_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; if (error_code != 0) { - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code + << " detected, halting visualization\n"; fprintf(gnuplot_pipe, "e\n"); fprintf(gnuplot_pipe, "exit \n"); pclose(gnuplot_pipe); return; } timestep_to_use = new_timestep; - evolved_distance = input_ground_station.distance_to_satellite(current_satellite); + evolved_distance = + input_ground_station.distance_to_satellite(current_satellite); previous_time = current_satellite_time; current_satellite_time = current_satellite.get_instantaneous_time(); - ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + ground_station_beam_angle = + input_ground_station.angle_to_satellite_from_normal( + current_satellite); // Check number of existing connections to ground station at this point - int num_sats_at_this_time = input_ground_station.num_sats_connected_at_this_time(current_satellite_time); - if ( (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) || (num_sats_at_this_time == input_ground_station.num_beams_)) { + int num_sats_at_this_time = + input_ground_station.num_sats_connected_at_this_time( + current_satellite_time); + if ((ground_station_beam_angle > + input_ground_station.max_beam_angle_from_normal_) || + (num_sats_at_this_time == input_ground_station.num_beams_)) { fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); - } - else { - evolved_distance = input_ground_station.distance_to_satellite(current_satellite); - fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, evolved_distance); - input_ground_station.update_linked_sats_map(satellite_index, current_satellite_time, previous_time); + } else { + evolved_distance = + input_ground_station.distance_to_satellite(current_satellite); + fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, + evolved_distance); + input_ground_station.update_linked_sats_map( + satellite_index, current_satellite_time, previous_time); } } fprintf(gnuplot_pipe, "e\n"); @@ -1404,14 +1442,12 @@ void sim_and_plot_gs_connectivity_distance_gnuplot( } return; - } -void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_station, - std::vector input_satellite_vector, - const SimParameters& input_sim_parameters, - const std::string file_name) { - +void sim_and_plot_gs_connectivity_gnuplot( + PhasedArrayGroundStation input_ground_station, + std::vector input_satellite_vector, + const SimParameters& input_sim_parameters, const std::string file_name) { // Objective: given an input ground station and satellite vector, // plot contact distances between ground station and satellites over time @@ -1421,21 +1457,26 @@ void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_ } // first, open "pipe" to gnuplot - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); // if it exists if (gnuplot_pipe) { - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, + "set terminal png size 800,500 font ',14' linewidth 2\n"); // formatting - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); fprintf(gnuplot_pipe, "set ylabel 'Satellite Index'\n"); - fprintf(gnuplot_pipe, "set title 'Phased array ground station connectivity " - "with %d beams'\n",input_ground_station.num_beams_); + fprintf(gnuplot_pipe, + "set title 'Phased array ground station connectivity " + "with %d beams'\n", + input_ground_station.num_beams_); fprintf(gnuplot_pipe, "set key outside\n"); - int x_max_plot_window = std::floor(input_sim_parameters.total_sim_time*1.05); - fprintf(gnuplot_pipe, "set xrange[0:%d]\n",x_max_plot_window); - fprintf(gnuplot_pipe, "set yrange[-0.5:%lu]\n",input_satellite_vector.size()); + int x_max_plot_window = + std::floor(input_sim_parameters.total_sim_time * 1.05); + fprintf(gnuplot_pipe, "set xrange[0:%d]\n", x_max_plot_window); + fprintf(gnuplot_pipe, "set yrange[-0.5:%lu]\n", + input_satellite_vector.size()); // plotting @@ -1469,7 +1510,7 @@ void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_ } for (size_t satellite_index = 1; - satellite_index < input_satellite_vector.size(); satellite_index++) { + satellite_index < input_satellite_vector.size(); satellite_index++) { current_satellite = input_satellite_vector.at(satellite_index); if (satellite_index < input_satellite_vector.size() - 1) { if (current_satellite.plotting_color_.size() > 0) { @@ -1501,33 +1542,39 @@ void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_ // now the orbit data, inline, one satellite at a time std::cout << "Running simulation...\n"; for (size_t satellite_index = 0; - satellite_index < input_satellite_vector.size(); satellite_index++) { + satellite_index < input_satellite_vector.size(); satellite_index++) { Satellite current_satellite = input_satellite_vector.at(satellite_index); double current_satellite_time = current_satellite.get_instantaneous_time(); double previous_time = current_satellite_time - 1; - double ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + double ground_station_beam_angle = + input_ground_station.angle_to_satellite_from_normal( + current_satellite); - if (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) { + if (ground_station_beam_angle > + input_ground_station.max_beam_angle_from_normal_) { fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); + } else { + fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, + satellite_index); } - else { - fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, satellite_index); - } - + double timestep_to_use = input_sim_parameters.initial_timestep_guess; current_satellite_time = current_satellite.get_instantaneous_time(); while (current_satellite_time < input_sim_parameters.total_sim_time) { - std::pair drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + std::pair drag_elements = {input_sim_parameters.F_10, + input_sim_parameters.A_p}; std::pair new_timestep_and_error_code = - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - input_sim_parameters.perturbation_bool, - input_sim_parameters.drag_bool, drag_elements); + current_satellite.evolve_RK45( + input_sim_parameters.epsilon, timestep_to_use, + input_sim_parameters.perturbation_bool, + input_sim_parameters.drag_bool, drag_elements); double new_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; if (error_code != 0) { - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code + << " detected, halting visualization\n"; fprintf(gnuplot_pipe, "e\n"); fprintf(gnuplot_pipe, "exit \n"); pclose(gnuplot_pipe); @@ -1536,15 +1583,22 @@ void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_ timestep_to_use = new_timestep; previous_time = current_satellite_time; current_satellite_time = current_satellite.get_instantaneous_time(); - ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + ground_station_beam_angle = + input_ground_station.angle_to_satellite_from_normal( + current_satellite); // Check number of existing connections to ground station at this point - int num_sats_at_this_time = input_ground_station.num_sats_connected_at_this_time(current_satellite_time); - if ( (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) || (num_sats_at_this_time == input_ground_station.num_beams_)) { + int num_sats_at_this_time = + input_ground_station.num_sats_connected_at_this_time( + current_satellite_time); + if ((ground_station_beam_angle > + input_ground_station.max_beam_angle_from_normal_) || + (num_sats_at_this_time == input_ground_station.num_beams_)) { fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); - } - else { - fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, satellite_index); - input_ground_station.update_linked_sats_map(satellite_index, current_satellite_time, previous_time); + } else { + fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, + satellite_index); + input_ground_station.update_linked_sats_map( + satellite_index, current_satellite_time, previous_time); } } fprintf(gnuplot_pipe, "e\n"); @@ -1567,16 +1621,17 @@ void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_ } return; - } - -int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double final_orbit_semimajor_axis_km, - const double input_thrust_magnitude, const double transfer_initiation_time) { +int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, + const double final_orbit_semimajor_axis_km, + const double input_thrust_magnitude, + const double transfer_initiation_time) { // Only transfers between circular orbits are supported at this time // Ref: https://prussing.ae.illinois.edu/AE402/low.thrust.pdf int error_code = 0; - double initial_eccentricity = input_satellite_object.get_orbital_parameter("Eccentricity"); + double initial_eccentricity = + input_satellite_object.get_orbital_parameter("Eccentricity"); if (initial_eccentricity != 0) { std::cout << "Satellite's initial orbit was not circular\n"; error_code = 1; @@ -1586,31 +1641,33 @@ int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double std::cout << "Error: satellite mass was <= 0\n"; error_code = 2; } - double thrust_acceleration = input_thrust_magnitude/satellite_mass; - double semimajor_axis_final = 1000 * final_orbit_semimajor_axis_km; // m - double semimajor_axis_initial = input_satellite_object.get_orbital_parameter("Semimajor Axis"); - const double mu_Earth = G*mass_Earth; - double comp1 =sqrt(mu_Earth/semimajor_axis_initial); - double comp2 = sqrt(mu_Earth/semimajor_axis_final); - double time_to_burn = (comp1-comp2)/thrust_acceleration; - - // Thrust is purely co-linear with velocity vector, so in the +- x direction of the LVLH frame - // (along +x if raising orbit, -x if lowering orbit) - std::array LVLH_thrust_direction; + double thrust_acceleration = input_thrust_magnitude / satellite_mass; + double semimajor_axis_final = 1000 * final_orbit_semimajor_axis_km; // m + double semimajor_axis_initial = + input_satellite_object.get_orbital_parameter("Semimajor Axis"); + const double mu_Earth = G * mass_Earth; + double comp1 = sqrt(mu_Earth / semimajor_axis_initial); + double comp2 = sqrt(mu_Earth / semimajor_axis_final); + double time_to_burn = (comp1 - comp2) / thrust_acceleration; + + // Thrust is purely co-linear with velocity vector, so in the +- x direction + // of the LVLH frame (along +x if raising orbit, -x if lowering orbit) + std::array LVLH_thrust_direction; if (semimajor_axis_initial < semimajor_axis_final) { - LVLH_thrust_direction = {1,0,0}; - } - else if (semimajor_axis_initial > semimajor_axis_final) { - LVLH_thrust_direction = {-1,0,0}; - time_to_burn = (-1)*time_to_burn; // Since this would have otherwise been negative - } - else { + LVLH_thrust_direction = {1, 0, 0}; + } else if (semimajor_axis_initial > semimajor_axis_final) { + LVLH_thrust_direction = {-1, 0, 0}; + time_to_burn = + (-1) * time_to_burn; // Since this would have otherwise been negative + } else { std::cout << "Error: initial and final semimajor axes were equal.\n"; - error_code = 3; // Arbitrarily choose a burn direction in this scenario, since it shouldn't matter + error_code = 3; // Arbitrarily choose a burn direction in this scenario, + // since it shouldn't matter } if (error_code == 0) { - input_satellite_object.add_LVLH_thrust_profile(LVLH_thrust_direction, input_thrust_magnitude, - transfer_initiation_time, transfer_initiation_time + time_to_burn); + input_satellite_object.add_LVLH_thrust_profile( + LVLH_thrust_direction, input_thrust_magnitude, transfer_initiation_time, + transfer_initiation_time + time_to_burn); } return error_code; } \ No newline at end of file From ef132bce5411533b4038583617ea79d939072211 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 02:13:39 -0700 Subject: [PATCH 4/7] Running clang-format on test cpp files --- tests/PhasedArrayGroundStation_tests.cpp | 33 +- tests/Satellite_tests.cpp | 438 ++++++----- tests/utils_tests.cpp | 940 ++++++++++++----------- 3 files changed, 772 insertions(+), 639 deletions(-) diff --git a/tests/PhasedArrayGroundStation_tests.cpp b/tests/PhasedArrayGroundStation_tests.cpp index 891b283..695f134 100644 --- a/tests/PhasedArrayGroundStation_tests.cpp +++ b/tests/PhasedArrayGroundStation_tests.cpp @@ -1,7 +1,8 @@ #include -#include #include +#include + #include "PhasedArrayGroundStation.h" #include "utils.h" @@ -11,20 +12,22 @@ TEST(PhasedArrayGroundStationTests, InitializationTest) { double gs_latitude = 2; double gs_longitude = 5; double gs_altitude = 10; - double max_beam_angle_from_normal = 65; //deg + double max_beam_angle_from_normal = 65; // deg int num_beams = 2; - PhasedArrayGroundStation example_ground_station(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); + PhasedArrayGroundStation example_ground_station( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); } TEST(PhasedArrayGroundStationTests, ECI_test_0) { double gs_latitude = 2; double gs_longitude = 5; double gs_altitude = 10; - double max_beam_angle_from_normal = 65; //deg + double max_beam_angle_from_normal = 65; // deg int num_beams = 2; - PhasedArrayGroundStation example_ground_station(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); + PhasedArrayGroundStation example_ground_station( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); Vector3d sample_ECI_position = example_ground_station.get_ECI_position(0); } @@ -32,11 +35,12 @@ TEST(PhasedArrayGroundStationTests, Evolved_ECI_test) { double gs_latitude = 2; double gs_longitude = 5; double gs_altitude = 10; - double max_beam_angle_from_normal = 65; //deg + double max_beam_angle_from_normal = 65; // deg int num_beams = 2; - PhasedArrayGroundStation example_ground_station(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); - + PhasedArrayGroundStation example_ground_station( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); + // Let's look at the difference over 10 seconds Vector3d initial_ECI_position = example_ground_station.get_ECI_position(0); Vector3d evolved_ECI_position = example_ground_station.get_ECI_position(10); @@ -44,8 +48,9 @@ TEST(PhasedArrayGroundStationTests, Evolved_ECI_test) { // Earth rotates to the east, and at J2000 the ECI y axis points East // but at J2000 there's a rotation angle of ~280 degrees between ECEF and ECI // so ECI x and y components should be increasing - EXPECT_TRUE(evolved_ECI_position(0) > initial_ECI_position(0)) << "Diff: " << evolved_ECI_position(0) - initial_ECI_position(0) << "\n"; - EXPECT_TRUE(evolved_ECI_position(1) > initial_ECI_position(1)) << "Diff: " << evolved_ECI_position(1) - initial_ECI_position(1) << "\n"; + EXPECT_TRUE(evolved_ECI_position(0) > initial_ECI_position(0)) + << "Diff: " << evolved_ECI_position(0) - initial_ECI_position(0) << "\n"; + EXPECT_TRUE(evolved_ECI_position(1) > initial_ECI_position(1)) + << "Diff: " << evolved_ECI_position(1) - initial_ECI_position(1) << "\n"; EXPECT_TRUE(evolved_ECI_position(2) == initial_ECI_position(2)); } - diff --git a/tests/Satellite_tests.cpp b/tests/Satellite_tests.cpp index 3863fd1..1633b55 100644 --- a/tests/Satellite_tests.cpp +++ b/tests/Satellite_tests.cpp @@ -6,10 +6,10 @@ #include "utils.h" const double tolerance = pow(10.0, -7); -// Setting a different tolerance for semimajor axis and orbital radius than the other orbital -// parameters since there appears to be a minimum error associated with -// converting position and velocity to semimajor axis, best guess is this has to -// do with the scale of distances and/or velocities being dealt with here +// Setting a different tolerance for semimajor axis and orbital radius than the +// other orbital parameters since there appears to be a minimum error associated +// with converting position and velocity to semimajor axis, best guess is this +// has to do with the scale of distances and/or velocities being dealt with here const double length_tolerance = pow(10.0, -6); const double epsilon = pow(10.0, -12); const double energy_cons_relative_tolerance = pow(10.0, -10); @@ -89,7 +89,7 @@ TEST(EllipticalOrbitTests, ConstantEvolvedOrbitalElementsTest) { if (orbital_elem_index == 0) { EXPECT_TRUE(abs(initial_orbit_elements.at(orbital_elem_index) - evolved_orbit_elements.at(orbital_elem_index)) < - length_tolerance) + length_tolerance) << orbital_element_name_array.at(orbital_elem_index) << " was not constant within tolerance. Diff:" << initial_orbit_elements.at(orbital_elem_index) - @@ -130,7 +130,7 @@ TEST(EllipticalOrbitTests, BasicOrbitalElementsTest) { if (orbital_elem_index == 0) { EXPECT_TRUE(abs(initial_orbit_elements.at(orbital_elem_index) - recalculated_orbit_elements.at(orbital_elem_index)) < - length_tolerance) + length_tolerance) << orbital_element_name_array.at(orbital_elem_index) << " was not constant within tolerance. Diff:" << initial_orbit_elements.at(orbital_elem_index) - @@ -149,17 +149,18 @@ TEST(EllipticalOrbitTests, BasicOrbitalElementsTest) { } } -TEST(EllipticalOrbitTests,OrbitalRadiusCalcs1) { +TEST(EllipticalOrbitTests, OrbitalRadiusCalcs1) { Satellite test_satellite("../tests/elliptical_orbit_test_2.json"); - double orbital_radius_perifocal=test_satellite.get_radius(); - double orbital_radius_ECI=test_satellite.get_radius_ECI(); - EXPECT_TRUE(abs(orbital_radius_perifocal - orbital_radius_ECI) < length_tolerance) + double orbital_radius_perifocal = test_satellite.get_radius(); + double orbital_radius_ECI = test_satellite.get_radius_ECI(); + EXPECT_TRUE(abs(orbital_radius_perifocal - orbital_radius_ECI) < + length_tolerance) << "Difference between orbital radii calculated with " - " perifocal and ECI coordinates: " - << orbital_radius_perifocal - orbital_radius_ECI <<"\n"; + " perifocal and ECI coordinates: " + << orbital_radius_perifocal - orbital_radius_ECI << "\n"; } -TEST(EllipticalOrbitTests,OrbitalRadiusCalcs2) { +TEST(EllipticalOrbitTests, OrbitalRadiusCalcs2) { Satellite test_satellite("../tests/elliptical_orbit_test_2.json"); double test_timestep = 0.1; // s bool perturbation_bool = false; @@ -167,26 +168,27 @@ TEST(EllipticalOrbitTests,OrbitalRadiusCalcs2) { test_satellite.evolve_RK45(epsilon, test_timestep, perturbation_bool); double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; - double orbital_radius_perifocal=test_satellite.get_radius(); - double orbital_radius_ECI=test_satellite.get_radius_ECI(); + double orbital_radius_perifocal = test_satellite.get_radius(); + double orbital_radius_ECI = test_satellite.get_radius_ECI(); - EXPECT_TRUE(abs(orbital_radius_perifocal - orbital_radius_ECI) < length_tolerance) + EXPECT_TRUE(abs(orbital_radius_perifocal - orbital_radius_ECI) < + length_tolerance) << "Difference between evolved orbital radii calculated with " - " perifocal and ECI coordinates: " - << orbital_radius_perifocal - orbital_radius_ECI <<"\n"; + " perifocal and ECI coordinates: " + << orbital_radius_perifocal - orbital_radius_ECI << "\n"; } -TEST(EllipticalOrbitTests,OrbitalSpeedCalcs1) { +TEST(EllipticalOrbitTests, OrbitalSpeedCalcs1) { Satellite test_satellite("../tests/elliptical_orbit_test_2.json"); - double orbital_speed_perifocal=test_satellite.get_speed(); - double orbital_speed_ECI=test_satellite.get_speed_ECI(); + double orbital_speed_perifocal = test_satellite.get_speed(); + double orbital_speed_ECI = test_satellite.get_speed_ECI(); EXPECT_TRUE(abs(orbital_speed_ECI - orbital_speed_perifocal) < tolerance) << "Difference between orbital speeds calculated with " - " perifocal and ECI coordinates: " - << orbital_speed_ECI - orbital_speed_perifocal <<"\n"; + " perifocal and ECI coordinates: " + << orbital_speed_ECI - orbital_speed_perifocal << "\n"; } -TEST(EllipticalOrbitTests,OrbitalSpeedCalcs2) { +TEST(EllipticalOrbitTests, OrbitalSpeedCalcs2) { Satellite test_satellite("../tests/elliptical_orbit_test_2.json"); double test_timestep = 0.1; // s bool perturbation_bool = false; @@ -194,13 +196,13 @@ TEST(EllipticalOrbitTests,OrbitalSpeedCalcs2) { test_satellite.evolve_RK45(epsilon, test_timestep, perturbation_bool); double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; - double orbital_speed_perifocal=test_satellite.get_speed(); - double orbital_speed_ECI=test_satellite.get_speed_ECI(); + double orbital_speed_perifocal = test_satellite.get_speed(); + double orbital_speed_ECI = test_satellite.get_speed_ECI(); EXPECT_TRUE(abs(orbital_speed_ECI - orbital_speed_perifocal) < tolerance) << "Difference between evolved orbital speeds calculated with " - " perifocal and ECI coordinates: " - << orbital_speed_ECI - orbital_speed_perifocal <<"\n"; + " perifocal and ECI coordinates: " + << orbital_speed_ECI - orbital_speed_perifocal << "\n"; } TEST(EllipticalOrbitTests, TotalEnergyTimestep1) { @@ -213,9 +215,11 @@ TEST(EllipticalOrbitTests, TotalEnergyTimestep1) { double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; double evolved_energy = test_satellite.get_total_energy(); - EXPECT_TRUE(abs(initial_energy - evolved_energy)/initial_energy < energy_cons_relative_tolerance) - << "Total energy not preserved within relative tolerance. Relative difference: " - << abs(initial_energy - evolved_energy)/initial_energy << "\n"; + EXPECT_TRUE(abs(initial_energy - evolved_energy) / initial_energy < + energy_cons_relative_tolerance) + << "Total energy not preserved within relative tolerance. Relative " + "difference: " + << abs(initial_energy - evolved_energy) / initial_energy << "\n"; } TEST(EllipticalOrbitTests, TotalEnergyTimestep2) { @@ -228,9 +232,11 @@ TEST(EllipticalOrbitTests, TotalEnergyTimestep2) { double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; double evolved_energy = test_satellite.get_total_energy(); - EXPECT_TRUE(abs(initial_energy - evolved_energy)/initial_energy < energy_cons_relative_tolerance) - << "Total energy not preserved within relative tolerance. Relative difference: " - << abs(initial_energy - evolved_energy)/initial_energy << "\n"; + EXPECT_TRUE(abs(initial_energy - evolved_energy) / initial_energy < + energy_cons_relative_tolerance) + << "Total energy not preserved within relative tolerance. Relative " + "difference: " + << abs(initial_energy - evolved_energy) / initial_energy << "\n"; } TEST(EllipticalOrbitTests, TotalEnergyTimestep3) { @@ -243,9 +249,11 @@ TEST(EllipticalOrbitTests, TotalEnergyTimestep3) { double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; double evolved_energy = test_satellite.get_total_energy(); - EXPECT_TRUE(abs(initial_energy - evolved_energy)/initial_energy < energy_cons_relative_tolerance) - << "Total energy not preserved within relative tolerance. Relative difference: " - << abs(initial_energy - evolved_energy)/initial_energy << "\n"; + EXPECT_TRUE(abs(initial_energy - evolved_energy) / initial_energy < + energy_cons_relative_tolerance) + << "Total energy not preserved within relative tolerance. Relative " + "difference: " + << abs(initial_energy - evolved_energy) / initial_energy << "\n"; } TEST(EllipticalOrbitTests, DragTest1) { @@ -254,90 +262,105 @@ TEST(EllipticalOrbitTests, DragTest1) { // Drag parameters double F_10 = 100; // Solar radio ten centimeter flux double A_p = 120; // Geomagnetic A_p index - double temp_epsilon = pow(10,-14); + double temp_epsilon = pow(10, -14); // Collect drag parameters into a pair with F_10 first and A_p second std::pair drag_elements = {F_10, A_p}; double test_timestep = 0.01; // s bool perturbation_bool = true; - double total_sim_time = 10; // s + double total_sim_time = 10; // s double current_time = test_satellite_nodrag.get_instantaneous_time(); double orbital_radius = 0; while (current_time < total_sim_time) { - std::pair new_timestep_and_error_code = - test_satellite_nodrag.evolve_RK45(temp_epsilon, test_timestep, perturbation_bool, - false); - orbital_radius = test_satellite_nodrag.get_radius(); - double altitude = (orbital_radius - radius_Earth)/1000.0; - double next_timestep = new_timestep_and_error_code.first; - test_timestep = next_timestep; - int error_code = new_timestep_and_error_code.second; - current_time = test_satellite_nodrag.get_instantaneous_time(); + std::pair new_timestep_and_error_code = + test_satellite_nodrag.evolve_RK45(temp_epsilon, test_timestep, + perturbation_bool, false); + orbital_radius = test_satellite_nodrag.get_radius(); + double altitude = (orbital_radius - radius_Earth) / 1000.0; + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time = test_satellite_nodrag.get_instantaneous_time(); } - double no_drag_semimajor_axis = test_satellite_nodrag.get_orbital_parameter("Semimajor Axis"); + double no_drag_semimajor_axis = + test_satellite_nodrag.get_orbital_parameter("Semimajor Axis"); current_time = test_satellite_withdrag.get_instantaneous_time(); while (current_time < total_sim_time) { - std::pair new_timestep_and_error_code = - test_satellite_withdrag.evolve_RK45(temp_epsilon, test_timestep, perturbation_bool, - true,drag_elements); - double next_timestep = new_timestep_and_error_code.first; - test_timestep = next_timestep; - int error_code = new_timestep_and_error_code.second; - current_time = test_satellite_withdrag.get_instantaneous_time(); + std::pair new_timestep_and_error_code = + test_satellite_withdrag.evolve_RK45(temp_epsilon, test_timestep, + perturbation_bool, true, + drag_elements); + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time = test_satellite_withdrag.get_instantaneous_time(); } - double with_drag_semimajor_axis = test_satellite_withdrag.get_orbital_parameter("Semimajor Axis"); + double with_drag_semimajor_axis = + test_satellite_withdrag.get_orbital_parameter("Semimajor Axis"); EXPECT_TRUE(no_drag_semimajor_axis > with_drag_semimajor_axis) - << "Semimajor axis after evolution wasn't lower when drag was introduced. " - "This isn't expected behavior. Difference: " << no_drag_semimajor_axis - with_drag_semimajor_axis << "\n"; + << "Semimajor axis after evolution wasn't lower when drag was " + "introduced. " + "This isn't expected behavior. Difference: " + << no_drag_semimajor_axis - with_drag_semimajor_axis << "\n"; } // Now trying to test the 140 < altitude < 180 km altitude section TEST(EllipticalOrbitTests, DragTest2) { - Satellite test_satellite_withdrag("../tests/circular_orbit_test_1_input.json"); + Satellite test_satellite_withdrag( + "../tests/circular_orbit_test_1_input.json"); Satellite test_satellite_nodrag("../tests/circular_orbit_test_1_input.json"); // Drag parameters double F_10 = 100; // Solar radio ten centimeter flux double A_p = 120; // Geomagnetic A_p index - double temp_epsilon = pow(10,-14); + double temp_epsilon = pow(10, -14); // Collect drag parameters into a pair with F_10 first and A_p second std::pair drag_elements = {F_10, A_p}; double test_timestep = 0.01; // s bool perturbation_bool = true; - double total_sim_time = 10; // s + double total_sim_time = 10; // s double current_time_nodrag = test_satellite_nodrag.get_instantaneous_time(); double orbital_radius = 0; while (current_time_nodrag < total_sim_time) { - std::pair new_timestep_and_error_code = - test_satellite_nodrag.evolve_RK45(temp_epsilon, test_timestep, perturbation_bool, - false); - orbital_radius = test_satellite_nodrag.get_radius(); - double altitude = (orbital_radius - radius_Earth)/1000.0; - double next_timestep = new_timestep_and_error_code.first; - test_timestep = next_timestep; - int error_code = new_timestep_and_error_code.second; - current_time_nodrag = test_satellite_nodrag.get_instantaneous_time(); + std::pair new_timestep_and_error_code = + test_satellite_nodrag.evolve_RK45(temp_epsilon, test_timestep, + perturbation_bool, false); + orbital_radius = test_satellite_nodrag.get_radius(); + double altitude = (orbital_radius - radius_Earth) / 1000.0; + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time_nodrag = test_satellite_nodrag.get_instantaneous_time(); } - double no_drag_semimajor_axis = test_satellite_nodrag.get_orbital_parameter("Semimajor Axis"); + double no_drag_semimajor_axis = + test_satellite_nodrag.get_orbital_parameter("Semimajor Axis"); - double current_time_withdrag = test_satellite_withdrag.get_instantaneous_time(); + double current_time_withdrag = + test_satellite_withdrag.get_instantaneous_time(); while (current_time_withdrag < total_sim_time) { - std::pair new_timestep_and_error_code = - test_satellite_withdrag.evolve_RK45(temp_epsilon, test_timestep, perturbation_bool, - true,drag_elements); - double next_timestep = new_timestep_and_error_code.first; - test_timestep = next_timestep; - int error_code = new_timestep_and_error_code.second; - current_time_withdrag = test_satellite_withdrag.get_instantaneous_time(); + std::pair new_timestep_and_error_code = + test_satellite_withdrag.evolve_RK45(temp_epsilon, test_timestep, + perturbation_bool, true, + drag_elements); + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time_withdrag = test_satellite_withdrag.get_instantaneous_time(); } - double with_drag_semimajor_axis = test_satellite_withdrag.get_orbital_parameter("Semimajor Axis"); + double with_drag_semimajor_axis = + test_satellite_withdrag.get_orbital_parameter("Semimajor Axis"); EXPECT_TRUE(no_drag_semimajor_axis > with_drag_semimajor_axis) - << "Semimajor axis after evolution wasn't lower when drag was introduced. " - "This isn't expected behavior. Difference: " << no_drag_semimajor_axis - with_drag_semimajor_axis << "\n" - " After-loop time without drag: " << current_time_nodrag << " and with drag: " << current_time_withdrag << "\n"; + << "Semimajor axis after evolution wasn't lower when drag was " + "introduced. " + "This isn't expected behavior. Difference: " + << no_drag_semimajor_axis - with_drag_semimajor_axis + << "\n" + " After-loop time without drag: " + << current_time_nodrag << " and with drag: " << current_time_withdrag + << "\n"; } TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver1) { @@ -349,35 +372,50 @@ TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver1) { double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; const double t_thrust_start = 0; - const double initial_arg_of_periapsis_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); - const double initial_arg_of_periapsis_rad = initial_arg_of_periapsis_deg*(M_PI/180.0); + const double initial_arg_of_periapsis_deg = + test_satellite.get_orbital_parameter("Argument of Periapsis"); + const double initial_arg_of_periapsis_rad = + initial_arg_of_periapsis_deg * (M_PI / 180.0); const double target_arg_of_periapsis_deg = initial_arg_of_periapsis_deg + 10; - const double target_arg_of_periapsis_rad = target_arg_of_periapsis_deg*(M_PI/180.0); - const double alpha = M_PI/2.0; // continous thrust - const double sign_of_delta_omega = 1.0; // because in this case, the final arg of periapsis is larger than the initial - const double thrust_magnitude = 0.1; // N - const double mu_Earth = G*mass_Earth; - const double delta_omega_mag = abs(target_arg_of_periapsis_rad - initial_arg_of_periapsis_rad); // = delta_omega / sgn(delta_omega) - const double satellite_a = test_satellite.get_orbital_parameter("Semimajor Axis"); - const double satellite_eccentricity = test_satellite.get_orbital_parameter("Eccentricity"); + const double target_arg_of_periapsis_rad = + target_arg_of_periapsis_deg * (M_PI / 180.0); + const double alpha = M_PI / 2.0; // continous thrust + const double sign_of_delta_omega = + 1.0; // because in this case, the final arg of periapsis is larger than + // the initial + const double thrust_magnitude = 0.1; // N + const double mu_Earth = G * mass_Earth; + const double delta_omega_mag = + abs(target_arg_of_periapsis_rad - + initial_arg_of_periapsis_rad); // = delta_omega / sgn(delta_omega) + const double satellite_a = + test_satellite.get_orbital_parameter("Semimajor Axis"); + const double satellite_eccentricity = + test_satellite.get_orbital_parameter("Eccentricity"); const double satellite_mass = test_satellite.get_mass(); - const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); - const double acceleration = thrust_magnitude/satellite_mass; - const double maneuver_length = delta_V/acceleration; + const double delta_V = + (2.0 / 3.0) * sqrt(mu_Earth / satellite_a) * satellite_eccentricity * + delta_omega_mag / + sqrt(1 - satellite_eccentricity * satellite_eccentricity); + const double acceleration = thrust_magnitude / satellite_mass; + const double maneuver_length = delta_V / acceleration; const double total_sim_time = maneuver_length + 10000; - double temp_epsilon = pow(10,-14); - test_satellite.add_maneuver("Argument of Periapsis Change",t_thrust_start,target_arg_of_periapsis_deg,thrust_magnitude); + double temp_epsilon = pow(10, -14); + test_satellite.add_maneuver("Argument of Periapsis Change", t_thrust_start, + target_arg_of_periapsis_deg, thrust_magnitude); double current_time = test_satellite.get_instantaneous_time(); while (current_time < total_sim_time) { std::pair new_timestep_and_error_code = - test_satellite.evolve_RK45(temp_epsilon, test_timestep, false); - double next_timestep = new_timestep_and_error_code.first; - test_timestep = next_timestep; - int error_code = new_timestep_and_error_code.second; - current_time = test_satellite.get_instantaneous_time(); - } - double arg_of_periapsis_final_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); - EXPECT_TRUE(abs(arg_of_periapsis_final_deg - target_arg_of_periapsis_deg) < 1); + test_satellite.evolve_RK45(temp_epsilon, test_timestep, false); + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time = test_satellite.get_instantaneous_time(); + } + double arg_of_periapsis_final_deg = + test_satellite.get_orbital_parameter("Argument of Periapsis"); + EXPECT_TRUE(abs(arg_of_periapsis_final_deg - target_arg_of_periapsis_deg) < + 1); } TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver2) { @@ -389,35 +427,50 @@ TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver2) { double next_timestep = new_timestep_and_error_code.first; int error_code = new_timestep_and_error_code.second; const double t_thrust_start = 0; - const double initial_arg_of_periapsis_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); - const double initial_arg_of_periapsis_rad = initial_arg_of_periapsis_deg*(M_PI/180.0); + const double initial_arg_of_periapsis_deg = + test_satellite.get_orbital_parameter("Argument of Periapsis"); + const double initial_arg_of_periapsis_rad = + initial_arg_of_periapsis_deg * (M_PI / 180.0); const double target_arg_of_periapsis_deg = initial_arg_of_periapsis_deg - 10; - const double target_arg_of_periapsis_rad = target_arg_of_periapsis_deg*(M_PI/180.0); - const double alpha = M_PI/2.0; // continous thrust - const double sign_of_delta_omega = 1.0; // because in this case, the final arg of periapsis is larger than the initial - const double thrust_magnitude = 0.1; // N - const double mu_Earth = G*mass_Earth; - const double delta_omega_mag = abs(target_arg_of_periapsis_rad - initial_arg_of_periapsis_rad); // = delta_omega / sgn(delta_omega) - const double satellite_a = test_satellite.get_orbital_parameter("Semimajor Axis"); - const double satellite_eccentricity = test_satellite.get_orbital_parameter("Eccentricity"); + const double target_arg_of_periapsis_rad = + target_arg_of_periapsis_deg * (M_PI / 180.0); + const double alpha = M_PI / 2.0; // continous thrust + const double sign_of_delta_omega = + 1.0; // because in this case, the final arg of periapsis is larger than + // the initial + const double thrust_magnitude = 0.1; // N + const double mu_Earth = G * mass_Earth; + const double delta_omega_mag = + abs(target_arg_of_periapsis_rad - + initial_arg_of_periapsis_rad); // = delta_omega / sgn(delta_omega) + const double satellite_a = + test_satellite.get_orbital_parameter("Semimajor Axis"); + const double satellite_eccentricity = + test_satellite.get_orbital_parameter("Eccentricity"); const double satellite_mass = test_satellite.get_mass(); - const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); - const double acceleration = thrust_magnitude/satellite_mass; - const double maneuver_length = delta_V/acceleration; + const double delta_V = + (2.0 / 3.0) * sqrt(mu_Earth / satellite_a) * satellite_eccentricity * + delta_omega_mag / + sqrt(1 - satellite_eccentricity * satellite_eccentricity); + const double acceleration = thrust_magnitude / satellite_mass; + const double maneuver_length = delta_V / acceleration; const double total_sim_time = maneuver_length + 10000; - double temp_epsilon = pow(10,-14); - test_satellite.add_maneuver("Argument of Periapsis Change",t_thrust_start,target_arg_of_periapsis_deg,thrust_magnitude); + double temp_epsilon = pow(10, -14); + test_satellite.add_maneuver("Argument of Periapsis Change", t_thrust_start, + target_arg_of_periapsis_deg, thrust_magnitude); double current_time = test_satellite.get_instantaneous_time(); while (current_time < total_sim_time) { std::pair new_timestep_and_error_code = - test_satellite.evolve_RK45(temp_epsilon, test_timestep, false); - double next_timestep = new_timestep_and_error_code.first; - test_timestep = next_timestep; - int error_code = new_timestep_and_error_code.second; - current_time = test_satellite.get_instantaneous_time(); - } - double arg_of_periapsis_final_deg = test_satellite.get_orbital_parameter("Argument of Periapsis"); - EXPECT_TRUE(abs(arg_of_periapsis_final_deg - target_arg_of_periapsis_deg) < 1); + test_satellite.evolve_RK45(temp_epsilon, test_timestep, false); + double next_timestep = new_timestep_and_error_code.first; + test_timestep = next_timestep; + int error_code = new_timestep_and_error_code.second; + current_time = test_satellite.get_instantaneous_time(); + } + double arg_of_periapsis_final_deg = + test_satellite.get_orbital_parameter("Argument of Periapsis"); + EXPECT_TRUE(abs(arg_of_periapsis_final_deg - target_arg_of_periapsis_deg) < + 1); } // Circular orbit tests @@ -463,9 +516,11 @@ TEST(CircularOrbitTests, TotalEnergyTimestep1) { int error_code = new_timestep_and_error_code.second; double evolved_energy = test_satellite.get_total_energy(); - EXPECT_TRUE(abs(initial_energy - evolved_energy)/initial_energy < energy_cons_relative_tolerance) - << "Total energy not preserved within relative tolerance. Relative difference: " - << abs(initial_energy - evolved_energy)/initial_energy << "\n"; + EXPECT_TRUE(abs(initial_energy - evolved_energy) / initial_energy < + energy_cons_relative_tolerance) + << "Total energy not preserved within relative tolerance. Relative " + "difference: " + << abs(initial_energy - evolved_energy) / initial_energy << "\n"; } TEST(CircularOrbitTests, EvolvedOrbitalRadius1) { @@ -635,9 +690,8 @@ TEST(CircularOrbitTests, Thruster_Eccentricity_Change) { << resulting_eccentricity << "\n"; } - // Attitude-related tests -const double pitch_tolerance = 0.25; // degrees +const double pitch_tolerance = 0.25; // degrees TEST(AttitudeTests, PassivePitchTest1) { // Without any external or initial torques, the satellite's pitch angle @@ -651,11 +705,13 @@ TEST(AttitudeTests, PassivePitchTest1) { double current_true_anomaly = initial_true_anomaly; double next_timestep = 0; bool wrapped_around = false; - while ((current_true_anomaly < initial_true_anomaly) || (wrapped_around == false)) { + while ((current_true_anomaly < initial_true_anomaly) || + (wrapped_around == false)) { std::pair new_timestep_and_error_code = test_satellite.evolve_RK45(epsilon, test_timestep); current_true_anomaly = test_satellite.get_orbital_parameter("True Anomaly"); - if ((!wrapped_around) && (0 <= current_true_anomaly) && (current_true_anomaly <= initial_true_anomaly)){ + if ((!wrapped_around) && (0 <= current_true_anomaly) && + (current_true_anomaly <= initial_true_anomaly)) { wrapped_around = true; } next_timestep = new_timestep_and_error_code.first; @@ -663,10 +719,9 @@ TEST(AttitudeTests, PassivePitchTest1) { test_timestep = next_timestep; } double evolved_pitch = test_satellite.get_attitude_val("Pitch"); - EXPECT_TRUE(abs(evolved_pitch - initial_pitch) < - pitch_tolerance) + EXPECT_TRUE(abs(evolved_pitch - initial_pitch) < pitch_tolerance) << "Pitch didn't progress 2*pi radians (within tolerance) " - "over one orbit as expected. Difference: " + "over one orbit as expected. Difference: " << evolved_pitch - initial_pitch << "\n"; } @@ -693,20 +748,21 @@ TEST(AttitudeTests, PassivePitchTest2) { << "Pitch didn't increase as expected\n"; } - // Misc tests TEST(MiscTests, ThrustProfileInitializationTest1) { double t_start = 1.0; double t_end = 9.0; - std::array thrust_vec = {1.0,101.2,-0.4}; - double magnitude = sqrt(pow(thrust_vec.at(0),2) + pow(thrust_vec.at(1),2) + pow(thrust_vec.at(2),2)); - std::array thrust_vec_direction = {0.0,0.0,0.0}; - for (size_t ind=0;ind thrust_vec = {1.0, 101.2, -0.4}; + double magnitude = sqrt(pow(thrust_vec.at(0), 2) + pow(thrust_vec.at(1), 2) + + pow(thrust_vec.at(2), 2)); + std::array thrust_vec_direction = {0.0, 0.0, 0.0}; + for (size_t ind = 0; ind < thrust_vec.size(); ind++) { + thrust_vec_direction.at(ind) = thrust_vec.at(ind) / magnitude; } - ThrustProfileLVLH thrust_profile_1(t_start,t_end,thrust_vec); - ThrustProfileLVLH thrust_profile_2(t_start,t_end,thrust_vec_direction,magnitude); + ThrustProfileLVLH thrust_profile_1(t_start, t_end, thrust_vec); + ThrustProfileLVLH thrust_profile_2(t_start, t_end, thrust_vec_direction, + magnitude); EXPECT_TRUE(thrust_profile_1 == thrust_profile_2) << "Thrust profiles initialized differently didn't agree.\n"; @@ -715,15 +771,17 @@ TEST(MiscTests, ThrustProfileInitializationTest1) { TEST(MiscTests, TorqueProfileInitializationTest1) { double t_start = 1.0; double t_end = 9.0; - std::array torque_vec = {1.0,101.2,-0.4}; - double magnitude = sqrt(pow(torque_vec.at(0),2) + pow(torque_vec.at(1),2) + pow(torque_vec.at(2),2)); - std::array torque_vec_direction = {0.0,0.0,0.0}; - for (size_t ind=0;ind torque_vec = {1.0, 101.2, -0.4}; + double magnitude = sqrt(pow(torque_vec.at(0), 2) + pow(torque_vec.at(1), 2) + + pow(torque_vec.at(2), 2)); + std::array torque_vec_direction = {0.0, 0.0, 0.0}; + for (size_t ind = 0; ind < torque_vec.size(); ind++) { + torque_vec_direction.at(ind) = torque_vec.at(ind) / magnitude; } - BodyframeTorqueProfile torque_profile_1(t_start,t_end,torque_vec); - BodyframeTorqueProfile torque_profile_2(t_start,t_end,torque_vec_direction,magnitude); + BodyframeTorqueProfile torque_profile_1(t_start, t_end, torque_vec); + BodyframeTorqueProfile torque_profile_2(t_start, t_end, torque_vec_direction, + magnitude); EXPECT_TRUE(torque_profile_1 == torque_profile_2) << "Torque profiles initialized differently didn't agree.\n"; @@ -734,13 +792,12 @@ TEST(MiscTests, ZeroInclinationTest) { bool caught = false; try { Satellite test_satellite("../tests/zero_inclination_test.json"); - } - catch( const std::invalid_argument& invalid_arg_error) { + } catch (const std::invalid_argument& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) - << "Didn't catch the invalid argument error expected for zero inclination\n"; + EXPECT_TRUE(caught) << "Didn't catch the invalid argument error expected for " + "zero inclination\n"; } // Make sure function to get name of Satellite is working as expected @@ -749,7 +806,6 @@ TEST(MiscTests, SatelliteNameTest) { std::string expected_name = "Circ_Test_1"; std::string recovered_name = test_satellite.get_name(); - EXPECT_TRUE(expected_name == recovered_name) << "Satellite name fetching didn't work as expected\n"; } @@ -760,13 +816,12 @@ TEST(MiscTests, AttitudeIncorrectNameTest) { bool caught = false; try { double val = test_satellite.get_attitude_val("This isn't a real name"); - } - catch( const std::invalid_argument& invalid_arg_error) { + } catch (const std::invalid_argument& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) - << "Didn't catch the invalid argument error expected for attitude val fetching\n"; + EXPECT_TRUE(caught) << "Didn't catch the invalid argument error expected for " + "attitude val fetching\n"; } TEST(MiscTests, OrbitElemIncorrectNameTest) { @@ -774,99 +829,98 @@ TEST(MiscTests, OrbitElemIncorrectNameTest) { bool caught = false; try { double val = test_satellite.get_orbital_parameter("This isn't a real name"); - } - catch( const std::invalid_argument& invalid_arg_error) { + } catch (const std::invalid_argument& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) - << "Didn't catch the invalid argument error expected for orbital parameter fetching\n"; + EXPECT_TRUE(caught) << "Didn't catch the invalid argument error expected for " + "orbital parameter fetching\n"; } TEST(MiscTests, NoInclination) { bool caught = false; try { Satellite test_satellite("../tests/no_inclination.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when inclination wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when inclination wasn't in input file\n"; } TEST(MiscTests, NoEccentricity) { bool caught = false; try { Satellite test_satellite("../tests/no_eccentricity.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when eccentricity wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when eccentricity wasn't in input file\n"; } TEST(MiscTests, NoArgofPeriapsis) { bool caught = false; try { Satellite test_satellite("../tests/no_arg_of_periapsis.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when argument of periapsis wasn't in input file\n"; + EXPECT_TRUE(caught) << "Didn't catch exception when argument of periapsis " + "wasn't in input file\n"; } TEST(MiscTests, NoRAAN) { bool caught = false; try { Satellite test_satellite("../tests/no_RAAN.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when RAAN wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when RAAN wasn't in input file\n"; } TEST(MiscTests, NoSemimajorAxis) { bool caught = false; try { Satellite test_satellite("../tests/no_semimajor_axis.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when semimajor axis wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when semimajor axis wasn't in input file\n"; } TEST(MiscTests, NoTrueAnomaly) { bool caught = false; try { Satellite test_satellite("../tests/no_true_anomaly.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when true anomaly wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when true anomaly wasn't in input file\n"; } TEST(MiscTests, NoName) { bool caught = false; try { Satellite test_satellite("../tests/no_name.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when satellite name wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when satellite name wasn't in input file\n"; } TEST(MiscTests, NoMass) { bool caught = false; try { Satellite test_satellite("../tests/no_mass.json"); - } - catch( const std::exception& invalid_arg_error) { + } catch (const std::exception& invalid_arg_error) { caught = true; } - EXPECT_TRUE(caught) << "Didn't catch exception when satellite mass wasn't in input file\n"; + EXPECT_TRUE(caught) + << "Didn't catch exception when satellite mass wasn't in input file\n"; } \ No newline at end of file diff --git a/tests/utils_tests.cpp b/tests/utils_tests.cpp index d6e6349..d2537ae 100644 --- a/tests/utils_tests.cpp +++ b/tests/utils_tests.cpp @@ -5,472 +5,546 @@ #include "Satellite.h" #include "utils.h" - TEST(UtilsTests, OrbitalElementPlottingTests) { - SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); - // Going to have one satellite with two thrust profiles and two torque profiles (added in different ways), - // one satellite with just two thrust profiles, one with just two torque profiles - // and one with none - Satellite test_sat_both("../tests/elliptical_orbit_test_1.json"); - // Define parameters for an LVLH frame thrust profile - std::array LVLH_thrust_direction = {1, 0, 0}; - double thrust_magnitude = 100; // N - double t_thrust_start = 0; - double t_thrust_end = 100; - // Add the thrust profile to the satellite object - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - - std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; - double t_thrust_2_start = 50; - double t_thrust_2_end = 150; - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); + SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); + // Going to have one satellite with two thrust profiles and two torque + // profiles (added in different ways), one satellite with just two thrust + // profiles, one with just two torque profiles and one with none + Satellite test_sat_both("../tests/elliptical_orbit_test_1.json"); + // Define parameters for an LVLH frame thrust profile + std::array LVLH_thrust_direction = {1, 0, 0}; + double thrust_magnitude = 100; // N + double t_thrust_start = 0; + double t_thrust_end = 100; + // Add the thrust profile to the satellite object + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, + t_thrust_start, t_thrust_end); + std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; + double t_thrust_2_start = 50; + double t_thrust_2_end = 150; + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); - std::array torque_direction = {0, -1, 0}; - double torque_magnitude = 0.0001; // N - double t_torque_start = 101; - double t_torque_end = 103; - test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - - std::array another_torque_vec = {-0.00001,0.00002,0.00003}; - test_sat_both.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_thrust("../tests/elliptical_orbit_test_1.json"); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); - - Satellite test_sat_torque("../tests/elliptical_orbit_test_4.json"); - test_sat_torque.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - test_sat_torque.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_none_1("../tests/elliptical_orbit_test_1.json"); - Satellite test_sat_none_2("../tests/elliptical_orbit_test_4.json"); - - std::vector satellite_vector_1 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_2 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - std::vector satellite_vector_3 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_4 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - - std::vector> satellite_vector_vector = {satellite_vector_1,satellite_vector_2,satellite_vector_3,satellite_vector_4}; - std::vector single_satellite_vec_1 = {test_sat_both}; - std::vector single_satellite_vec_2 = {test_sat_torque}; - satellite_vector_vector.push_back(single_satellite_vec_1); - satellite_vector_vector.push_back(single_satellite_vec_2); - sim_parameters.initial_timestep_guess = 2; - sim_parameters.total_sim_time = 300; - - // Drag parameters - sim_parameters.F_10 = 100; // Solar radio ten centimeter flux - sim_parameters.A_p = 120; // Geomagnetic A_p index - - // Collect drag parameters into a tuple with F_10 first and A_p second - std::string file_name = "test_plot"; - std::vector orbital_elements = {"Semimajor Axis", - "Eccentricity","Inclination","RAAN", - "Argument of Periapsis","True Anomaly", - "Orbital Rate","Orbital Angular Acceleration", - "Total Energy"}; - for (std::vector satellite_vector : satellite_vector_vector){ - for (std::string element_name : orbital_elements){ - sim_parameters.perturbation_bool = false; - sim_parameters.drag_bool = false; - sim_and_plot_orbital_elem_gnuplot(satellite_vector, sim_parameters, element_name, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = false; - sim_and_plot_orbital_elem_gnuplot(satellite_vector, sim_parameters, element_name, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = true; - sim_and_plot_orbital_elem_gnuplot(satellite_vector, sim_parameters, element_name, file_name); - } + std::array torque_direction = {0, -1, 0}; + double torque_magnitude = 0.0001; // N + double t_torque_start = 101; + double t_torque_end = 103; + test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, + t_torque_start, t_torque_end); + + std::array another_torque_vec = {-0.00001, 0.00002, 0.00003}; + test_sat_both.add_bodyframe_torque_profile(another_torque_vec, t_torque_start, + t_torque_end); + + Satellite test_sat_thrust("../tests/elliptical_orbit_test_1.json"); + test_sat_thrust.add_LVLH_thrust_profile( + LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); + test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); + + Satellite test_sat_torque("../tests/elliptical_orbit_test_4.json"); + test_sat_torque.add_bodyframe_torque_profile( + torque_direction, torque_magnitude, t_torque_start, t_torque_end); + test_sat_torque.add_bodyframe_torque_profile(another_torque_vec, + t_torque_start, t_torque_end); + + Satellite test_sat_none_1("../tests/elliptical_orbit_test_1.json"); + Satellite test_sat_none_2("../tests/elliptical_orbit_test_4.json"); + + std::vector satellite_vector_1 = {test_sat_none_1, test_sat_none_2, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_2 = { + test_sat_none_1, test_sat_none_2, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + std::vector satellite_vector_3 = {test_sat_none_2, test_sat_none_1, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_4 = { + test_sat_none_2, test_sat_none_1, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + + std::vector> satellite_vector_vector = { + satellite_vector_1, satellite_vector_2, satellite_vector_3, + satellite_vector_4}; + std::vector single_satellite_vec_1 = {test_sat_both}; + std::vector single_satellite_vec_2 = {test_sat_torque}; + satellite_vector_vector.push_back(single_satellite_vec_1); + satellite_vector_vector.push_back(single_satellite_vec_2); + sim_parameters.initial_timestep_guess = 2; + sim_parameters.total_sim_time = 300; + + // Drag parameters + sim_parameters.F_10 = 100; // Solar radio ten centimeter flux + sim_parameters.A_p = 120; // Geomagnetic A_p index + + // Collect drag parameters into a tuple with F_10 first and A_p second + std::string file_name = "test_plot"; + std::vector orbital_elements = { + "Semimajor Axis", "Eccentricity", + "Inclination", "RAAN", + "Argument of Periapsis", "True Anomaly", + "Orbital Rate", "Orbital Angular Acceleration", + "Total Energy"}; + for (std::vector satellite_vector : satellite_vector_vector) { + for (std::string element_name : orbital_elements) { + sim_parameters.perturbation_bool = false; + sim_parameters.drag_bool = false; + sim_and_plot_orbital_elem_gnuplot(satellite_vector, sim_parameters, + element_name, file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = false; + sim_and_plot_orbital_elem_gnuplot(satellite_vector, sim_parameters, + element_name, file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = true; + sim_and_plot_orbital_elem_gnuplot(satellite_vector, sim_parameters, + element_name, file_name); } - } - +} // Now a similar test for attitude plotting TEST(UtilsTests, AttitudeElementPlottingTests) { - // Going to have one satellite with two thrust profiles and two torque profiles (added in different ways), - // one satellite with just two thrust profiles, one with just two torque profiles - // and one with none - SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); - Satellite test_sat_both("../tests/elliptical_orbit_test_1.json"); - // Define parameters for an LVLH frame thrust profile - std::array LVLH_thrust_direction = {1, 0, 0}; - double thrust_magnitude = 100; // N - double t_thrust_start = 50; - double t_thrust_end = 150; - // Add the thrust profile to the satellite object - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - - std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; - double t_thrust_2_start = 0; - double t_thrust_2_end = 100; - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); + // Going to have one satellite with two thrust profiles and two torque + // profiles (added in different ways), one satellite with just two thrust + // profiles, one with just two torque profiles and one with none + SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); + Satellite test_sat_both("../tests/elliptical_orbit_test_1.json"); + // Define parameters for an LVLH frame thrust profile + std::array LVLH_thrust_direction = {1, 0, 0}; + double thrust_magnitude = 100; // N + double t_thrust_start = 50; + double t_thrust_end = 150; + // Add the thrust profile to the satellite object + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, + t_thrust_start, t_thrust_end); + std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; + double t_thrust_2_start = 0; + double t_thrust_2_end = 100; + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); - std::array torque_direction = {0, -1, 0}; - double torque_magnitude = 0.0001; // N - double t_torque_start = 101; - double t_torque_end = 103; - test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - - std::array another_torque_vec = {-0.00001,0.00002,0.00003}; - test_sat_both.add_bodyframe_torque_profile(another_torque_vec,0,2); - - Satellite test_sat_thrust("../tests/elliptical_orbit_test_1.json"); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); - - Satellite test_sat_torque("../tests/elliptical_orbit_test_4.json"); - test_sat_torque.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - test_sat_torque.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_none_1("../tests/elliptical_orbit_test_1.json"); - Satellite test_sat_none_2("../tests/elliptical_orbit_test_4.json"); - - std::vector satellite_vector_1 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_2 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - std::vector satellite_vector_3 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_4 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - - std::vector> satellite_vector_vector = {satellite_vector_1,satellite_vector_2,satellite_vector_3,satellite_vector_4}; - std::vector single_satellite_vec_1 = {test_sat_both}; - std::vector single_satellite_vec_2 = {test_sat_torque}; - satellite_vector_vector.push_back(single_satellite_vec_1); - satellite_vector_vector.push_back(single_satellite_vec_2); - - sim_parameters.initial_timestep_guess = 2; - sim_parameters.total_sim_time = 300; - - // Drag parameters - sim_parameters.F_10 = 100; // Solar radio ten centimeter flux - sim_parameters.A_p = 120; // Geomagnetic A_p index - - std::string file_name = "test_plot"; - std::vector attitude_elements = {"Roll", - "Pitch","Yaw","omega_x", - "omega_y","omega_z", - "q_0","q_1","q_2","q_3"}; - for (std::vector satellite_vector : satellite_vector_vector){ - for (std::string element_name : attitude_elements){ - sim_parameters.perturbation_bool = false; - sim_parameters.drag_bool = false; - sim_and_plot_attitude_evolution_gnuplot(satellite_vector, sim_parameters, element_name, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = false; - sim_and_plot_attitude_evolution_gnuplot(satellite_vector, sim_parameters, element_name, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = true; - sim_and_plot_attitude_evolution_gnuplot(satellite_vector, sim_parameters, element_name, file_name); - } + std::array torque_direction = {0, -1, 0}; + double torque_magnitude = 0.0001; // N + double t_torque_start = 101; + double t_torque_end = 103; + test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, + t_torque_start, t_torque_end); + + std::array another_torque_vec = {-0.00001, 0.00002, 0.00003}; + test_sat_both.add_bodyframe_torque_profile(another_torque_vec, 0, 2); + + Satellite test_sat_thrust("../tests/elliptical_orbit_test_1.json"); + test_sat_thrust.add_LVLH_thrust_profile( + LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); + test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); + + Satellite test_sat_torque("../tests/elliptical_orbit_test_4.json"); + test_sat_torque.add_bodyframe_torque_profile( + torque_direction, torque_magnitude, t_torque_start, t_torque_end); + test_sat_torque.add_bodyframe_torque_profile(another_torque_vec, + t_torque_start, t_torque_end); + + Satellite test_sat_none_1("../tests/elliptical_orbit_test_1.json"); + Satellite test_sat_none_2("../tests/elliptical_orbit_test_4.json"); + + std::vector satellite_vector_1 = {test_sat_none_1, test_sat_none_2, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_2 = { + test_sat_none_1, test_sat_none_2, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + std::vector satellite_vector_3 = {test_sat_none_2, test_sat_none_1, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_4 = { + test_sat_none_2, test_sat_none_1, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + + std::vector> satellite_vector_vector = { + satellite_vector_1, satellite_vector_2, satellite_vector_3, + satellite_vector_4}; + std::vector single_satellite_vec_1 = {test_sat_both}; + std::vector single_satellite_vec_2 = {test_sat_torque}; + satellite_vector_vector.push_back(single_satellite_vec_1); + satellite_vector_vector.push_back(single_satellite_vec_2); + + sim_parameters.initial_timestep_guess = 2; + sim_parameters.total_sim_time = 300; + + // Drag parameters + sim_parameters.F_10 = 100; // Solar radio ten centimeter flux + sim_parameters.A_p = 120; // Geomagnetic A_p index + + std::string file_name = "test_plot"; + std::vector attitude_elements = { + "Roll", "Pitch", "Yaw", "omega_x", "omega_y", + "omega_z", "q_0", "q_1", "q_2", "q_3"}; + for (std::vector satellite_vector : satellite_vector_vector) { + for (std::string element_name : attitude_elements) { + sim_parameters.perturbation_bool = false; + sim_parameters.drag_bool = false; + sim_and_plot_attitude_evolution_gnuplot(satellite_vector, sim_parameters, + element_name, file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = false; + sim_and_plot_attitude_evolution_gnuplot(satellite_vector, sim_parameters, + element_name, file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = true; + sim_and_plot_attitude_evolution_gnuplot(satellite_vector, sim_parameters, + element_name, file_name); } } +} - // Now one for the 3D orbital plot - TEST(UtilsTests, ThreeDimensionalOrbitPlotTest) { - // Going to have one satellite with two thrust profiles and two torque profiles (added in different ways), - // one satellite with just two thrust profiles, one with just two torque profiles - // and one with none - SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); - Satellite test_sat_both("../tests/elliptical_orbit_test_1.json"); - // Define parameters for an LVLH frame thrust profile - std::array LVLH_thrust_direction = {1, 0, 0}; - double thrust_magnitude = 100; // N - double t_thrust_start = 0; - double t_thrust_end = 100; - // Add the thrust profile to the satellite object - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - - std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; - double t_thrust_2_start = 50; - double t_thrust_2_end = 150; - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); - +// Now one for the 3D orbital plot +TEST(UtilsTests, ThreeDimensionalOrbitPlotTest) { + // Going to have one satellite with two thrust profiles and two torque + // profiles (added in different ways), one satellite with just two thrust + // profiles, one with just two torque profiles and one with none + SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); + Satellite test_sat_both("../tests/elliptical_orbit_test_1.json"); + // Define parameters for an LVLH frame thrust profile + std::array LVLH_thrust_direction = {1, 0, 0}; + double thrust_magnitude = 100; // N + double t_thrust_start = 0; + double t_thrust_end = 100; + // Add the thrust profile to the satellite object + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, + t_thrust_start, t_thrust_end); - std::array torque_direction = {0, -1, 0}; - double torque_magnitude = 0.0001; // N - double t_torque_start = 101; - double t_torque_end = 103; - test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - - std::array another_torque_vec = {-0.00001,0.00002,0.00003}; - test_sat_both.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_thrust("../tests/elliptical_orbit_test_1.json"); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); - - Satellite test_sat_torque("../tests/elliptical_orbit_test_4.json"); - test_sat_torque.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - test_sat_torque.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_none_1("../tests/elliptical_orbit_test_1.json"); - Satellite test_sat_none_2("../tests/elliptical_orbit_test_4.json"); - - std::vector satellite_vector_1 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_2 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - std::vector satellite_vector_3 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_4 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - - std::vector> satellite_vector_vector = {satellite_vector_1,satellite_vector_2,satellite_vector_3,satellite_vector_4}; - std::vector single_satellite_vec_1 = {test_sat_both}; - std::vector single_satellite_vec_2 = {test_sat_torque}; - satellite_vector_vector.push_back(single_satellite_vec_1); - satellite_vector_vector.push_back(single_satellite_vec_2); - - sim_parameters.initial_timestep_guess = 2; - sim_parameters.total_sim_time = 300; - - // Drag parameters - sim_parameters.F_10 = 100; // Solar radio ten centimeter flux - sim_parameters.A_p = 120; // Geomagnetic A_p index - - sim_parameters.terminal_name_3D = "png"; // qt terminal opens window, probably not suited to running on a remote Github actions runner - const std::string output_file_name = "test_plot"; - - for (std::vector satellite_vector : satellite_vector_vector){ - sim_parameters.perturbation_bool = false; - sim_parameters.drag_bool = false; - sim_and_draw_orbit_gnuplot(satellite_vector, sim_parameters, output_file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = false; - sim_and_draw_orbit_gnuplot(satellite_vector, sim_parameters, output_file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = true; - sim_and_draw_orbit_gnuplot(satellite_vector, sim_parameters, output_file_name); - } + std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; + double t_thrust_2_start = 50; + double t_thrust_2_end = 150; + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); + std::array torque_direction = {0, -1, 0}; + double torque_magnitude = 0.0001; // N + double t_torque_start = 101; + double t_torque_end = 103; + test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, + t_torque_start, t_torque_end); + + std::array another_torque_vec = {-0.00001, 0.00002, 0.00003}; + test_sat_both.add_bodyframe_torque_profile(another_torque_vec, t_torque_start, + t_torque_end); + + Satellite test_sat_thrust("../tests/elliptical_orbit_test_1.json"); + test_sat_thrust.add_LVLH_thrust_profile( + LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); + test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); + + Satellite test_sat_torque("../tests/elliptical_orbit_test_4.json"); + test_sat_torque.add_bodyframe_torque_profile( + torque_direction, torque_magnitude, t_torque_start, t_torque_end); + test_sat_torque.add_bodyframe_torque_profile(another_torque_vec, + t_torque_start, t_torque_end); + + Satellite test_sat_none_1("../tests/elliptical_orbit_test_1.json"); + Satellite test_sat_none_2("../tests/elliptical_orbit_test_4.json"); + + std::vector satellite_vector_1 = {test_sat_none_1, test_sat_none_2, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_2 = { + test_sat_none_1, test_sat_none_2, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + std::vector satellite_vector_3 = {test_sat_none_2, test_sat_none_1, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_4 = { + test_sat_none_2, test_sat_none_1, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + + std::vector> satellite_vector_vector = { + satellite_vector_1, satellite_vector_2, satellite_vector_3, + satellite_vector_4}; + std::vector single_satellite_vec_1 = {test_sat_both}; + std::vector single_satellite_vec_2 = {test_sat_torque}; + satellite_vector_vector.push_back(single_satellite_vec_1); + satellite_vector_vector.push_back(single_satellite_vec_2); + + sim_parameters.initial_timestep_guess = 2; + sim_parameters.total_sim_time = 300; + + // Drag parameters + sim_parameters.F_10 = 100; // Solar radio ten centimeter flux + sim_parameters.A_p = 120; // Geomagnetic A_p index + + sim_parameters.terminal_name_3D = + "png"; // qt terminal opens window, probably not suited to running on a + // remote Github actions runner + const std::string output_file_name = "test_plot"; + + for (std::vector satellite_vector : satellite_vector_vector) { + sim_parameters.perturbation_bool = false; + sim_parameters.drag_bool = false; + sim_and_draw_orbit_gnuplot(satellite_vector, sim_parameters, + output_file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = false; + sim_and_draw_orbit_gnuplot(satellite_vector, sim_parameters, + output_file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = true; + sim_and_draw_orbit_gnuplot(satellite_vector, sim_parameters, + output_file_name); } - +} TEST(UtilsTests, GroundStationConnectivityDistancePlotTests) { - // Going to have one satellite with two thrust profiles and two torque profiles (added in different ways), - // one satellite with just two thrust profiles, one with just two torque profiles - // and one with none - SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); - Satellite test_sat_both("../tests/input_2.json"); - // Define parameters for an LVLH frame thrust profile - std::array LVLH_thrust_direction = {1, 0, 0}; - double thrust_magnitude = 100; // N - double t_thrust_start = 0; - double t_thrust_end = 100; - // Add the thrust profile to the satellite object - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, + // Going to have one satellite with two thrust profiles and two torque + // profiles (added in different ways), one satellite with just two thrust + // profiles, one with just two torque profiles and one with none + SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); + Satellite test_sat_both("../tests/input_2.json"); + // Define parameters for an LVLH frame thrust profile + std::array LVLH_thrust_direction = {1, 0, 0}; + double thrust_magnitude = 100; // N + double t_thrust_start = 0; + double t_thrust_end = 100; + // Add the thrust profile to the satellite object + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); - std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; - double t_thrust_2_start = 50; - double t_thrust_2_end = 150; - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; + double t_thrust_2_start = 50; + double t_thrust_2_end = 150; + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, t_thrust_2_end); - - std::array torque_direction = {0, -1, 0}; - double torque_magnitude = 0.0001; // N - double t_torque_start = 101; - double t_torque_end = 103; - test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - - std::array another_torque_vec = {-0.00001,0.00002,0.00003}; - test_sat_both.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_thrust("../tests/input_2.json"); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); - - Satellite test_sat_torque("../tests/input_3.json"); - test_sat_torque.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - test_sat_torque.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_none_1("../tests/input_2.json"); - Satellite test_sat_none_2("../tests/input_3.json"); - - std::vector satellite_vector_1 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_2 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - std::vector satellite_vector_3 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_4 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - - std::vector> satellite_vector_vector = {satellite_vector_1,satellite_vector_2,satellite_vector_3,satellite_vector_4}; - std::vector single_satellite_vec_1 = {test_sat_both}; - std::vector single_satellite_vec_2 = {test_sat_torque}; - satellite_vector_vector.push_back(single_satellite_vec_1); - satellite_vector_vector.push_back(single_satellite_vec_2); - sim_parameters.initial_timestep_guess = 2; - sim_parameters.total_sim_time = 300; - - // Drag parameters - sim_parameters.F_10 = 100; // Solar radio ten centimeter flux - sim_parameters.A_p = 120; // Geomagnetic A_p index - - - double gs_latitude = 2; - double gs_longitude = 5; - double gs_altitude = 10; - double max_beam_angle_from_normal = 65; //deg - int num_beams = 2; - sim_parameters.total_sim_time = 25000; - PhasedArrayGroundStation example_ground_station_1(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); - - std::string file_name = "test_plot"; - std::vector orbital_elements = {"Semimajor Axis", - "Eccentricity","Inclination","RAAN", - "Argument of Periapsis","True Anomaly", - "Orbital Rate","Orbital Angular Acceleration", - "Total Energy"}; - for (std::vector satellite_vector : satellite_vector_vector){ - for (std::string element_name : orbital_elements){ - sim_parameters.perturbation_bool = false; - sim_parameters.drag_bool = false; - sim_and_plot_gs_connectivity_distance_gnuplot(example_ground_station_1, satellite_vector, sim_parameters, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = false; - sim_and_plot_gs_connectivity_distance_gnuplot(example_ground_station_1, satellite_vector, sim_parameters, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = true; - sim_and_plot_gs_connectivity_distance_gnuplot(example_ground_station_1, satellite_vector, sim_parameters, file_name); - } + std::array torque_direction = {0, -1, 0}; + double torque_magnitude = 0.0001; // N + double t_torque_start = 101; + double t_torque_end = 103; + test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, + t_torque_start, t_torque_end); + + std::array another_torque_vec = {-0.00001, 0.00002, 0.00003}; + test_sat_both.add_bodyframe_torque_profile(another_torque_vec, t_torque_start, + t_torque_end); + + Satellite test_sat_thrust("../tests/input_2.json"); + test_sat_thrust.add_LVLH_thrust_profile( + LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); + test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); + + Satellite test_sat_torque("../tests/input_3.json"); + test_sat_torque.add_bodyframe_torque_profile( + torque_direction, torque_magnitude, t_torque_start, t_torque_end); + test_sat_torque.add_bodyframe_torque_profile(another_torque_vec, + t_torque_start, t_torque_end); + + Satellite test_sat_none_1("../tests/input_2.json"); + Satellite test_sat_none_2("../tests/input_3.json"); + + std::vector satellite_vector_1 = {test_sat_none_1, test_sat_none_2, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_2 = { + test_sat_none_1, test_sat_none_2, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + std::vector satellite_vector_3 = {test_sat_none_2, test_sat_none_1, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_4 = { + test_sat_none_2, test_sat_none_1, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + + std::vector> satellite_vector_vector = { + satellite_vector_1, satellite_vector_2, satellite_vector_3, + satellite_vector_4}; + std::vector single_satellite_vec_1 = {test_sat_both}; + std::vector single_satellite_vec_2 = {test_sat_torque}; + satellite_vector_vector.push_back(single_satellite_vec_1); + satellite_vector_vector.push_back(single_satellite_vec_2); + sim_parameters.initial_timestep_guess = 2; + sim_parameters.total_sim_time = 300; + + // Drag parameters + sim_parameters.F_10 = 100; // Solar radio ten centimeter flux + sim_parameters.A_p = 120; // Geomagnetic A_p index + + double gs_latitude = 2; + double gs_longitude = 5; + double gs_altitude = 10; + double max_beam_angle_from_normal = 65; // deg + int num_beams = 2; + sim_parameters.total_sim_time = 25000; + PhasedArrayGroundStation example_ground_station_1( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); + + std::string file_name = "test_plot"; + std::vector orbital_elements = { + "Semimajor Axis", "Eccentricity", + "Inclination", "RAAN", + "Argument of Periapsis", "True Anomaly", + "Orbital Rate", "Orbital Angular Acceleration", + "Total Energy"}; + for (std::vector satellite_vector : satellite_vector_vector) { + for (std::string element_name : orbital_elements) { + sim_parameters.perturbation_bool = false; + sim_parameters.drag_bool = false; + sim_and_plot_gs_connectivity_distance_gnuplot(example_ground_station_1, + satellite_vector, + sim_parameters, file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = false; + sim_and_plot_gs_connectivity_distance_gnuplot(example_ground_station_1, + satellite_vector, + sim_parameters, file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = true; + sim_and_plot_gs_connectivity_distance_gnuplot(example_ground_station_1, + satellite_vector, + sim_parameters, file_name); } - + } } - - TEST(UtilsTests, GroundStationConnectivityPlotTests) { - // Going to have one satellite with two thrust profiles and two torque profiles (added in different ways), - // one satellite with just two thrust profiles, one with just two torque profiles - // and one with none - SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); - Satellite test_sat_both("../tests/input_2.json"); - // Define parameters for an LVLH frame thrust profile - std::array LVLH_thrust_direction = {1, 0, 0}; - double thrust_magnitude = 100; // N - double t_thrust_start = 0; - double t_thrust_end = 100; - // Add the thrust profile to the satellite object - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, + // Going to have one satellite with two thrust profiles and two torque + // profiles (added in different ways), one satellite with just two thrust + // profiles, one with just two torque profiles and one with none + SimParameters sim_parameters("../tests/sim_parameters_baseline.json"); + Satellite test_sat_both("../tests/input_2.json"); + // Define parameters for an LVLH frame thrust profile + std::array LVLH_thrust_direction = {1, 0, 0}; + double thrust_magnitude = 100; // N + double t_thrust_start = 0; + double t_thrust_end = 100; + // Add the thrust profile to the satellite object + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); - std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; - double t_thrust_2_start = 50; - double t_thrust_2_end = 150; - test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + std::array LVLH_thrust_vec_2 = {0.51, 20, -5}; + double t_thrust_2_start = 50; + double t_thrust_2_end = 150; + test_sat_both.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, t_thrust_2_end); - - std::array torque_direction = {0, -1, 0}; - double torque_magnitude = 0.0001; // N - double t_torque_start = 101; - double t_torque_end = 103; - test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - - std::array another_torque_vec = {-0.00001,0.00002,0.00003}; - test_sat_both.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_thrust("../tests/input_2.json"); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_direction, thrust_magnitude, - t_thrust_start, t_thrust_end); - test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, - t_thrust_2_end); - - Satellite test_sat_torque("../tests/input_3.json"); - test_sat_torque.add_bodyframe_torque_profile(torque_direction, torque_magnitude, - t_torque_start, t_torque_end); - test_sat_torque.add_bodyframe_torque_profile(another_torque_vec,t_torque_start,t_torque_end); - - Satellite test_sat_none_1("../tests/input_2.json"); - Satellite test_sat_none_2("../tests/input_3.json"); - - std::vector satellite_vector_1 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_2 = {test_sat_none_1,test_sat_none_2,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - std::vector satellite_vector_3 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both}; - std::vector satellite_vector_4 = {test_sat_none_2,test_sat_none_1,test_sat_thrust,test_sat_torque,test_sat_both,test_sat_none_2}; - - std::vector> satellite_vector_vector = {satellite_vector_1,satellite_vector_2,satellite_vector_3,satellite_vector_4}; - std::vector single_satellite_vec_1 = {test_sat_both}; - std::vector single_satellite_vec_2 = {test_sat_torque}; - satellite_vector_vector.push_back(single_satellite_vec_1); - satellite_vector_vector.push_back(single_satellite_vec_2); - sim_parameters.initial_timestep_guess = 2; - sim_parameters.total_sim_time = 300; - - // Drag parameters - sim_parameters.F_10 = 100; // Solar radio ten centimeter flux - sim_parameters.A_p = 120; // Geomagnetic A_p index - - - double gs_latitude = 2; - double gs_longitude = 5; - double gs_altitude = 10; - double max_beam_angle_from_normal = 65; //deg - int num_beams = 2; - sim_parameters.total_sim_time = 25000; - PhasedArrayGroundStation example_ground_station_1(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); - - std::string file_name = "test_plot"; - std::vector orbital_elements = {"Semimajor Axis", - "Eccentricity","Inclination","RAAN", - "Argument of Periapsis","True Anomaly", - "Orbital Rate","Orbital Angular Acceleration", - "Total Energy"}; - for (std::vector satellite_vector : satellite_vector_vector){ - for (std::string element_name : orbital_elements){ - sim_parameters.perturbation_bool = false; - sim_parameters.drag_bool = false; - sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, satellite_vector, sim_parameters, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = false; - sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, satellite_vector, sim_parameters, file_name); - sim_parameters.perturbation_bool = true; - sim_parameters.drag_bool = true; - sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, satellite_vector, sim_parameters, file_name); - } + std::array torque_direction = {0, -1, 0}; + double torque_magnitude = 0.0001; // N + double t_torque_start = 101; + double t_torque_end = 103; + test_sat_both.add_bodyframe_torque_profile(torque_direction, torque_magnitude, + t_torque_start, t_torque_end); + + std::array another_torque_vec = {-0.00001, 0.00002, 0.00003}; + test_sat_both.add_bodyframe_torque_profile(another_torque_vec, t_torque_start, + t_torque_end); + + Satellite test_sat_thrust("../tests/input_2.json"); + test_sat_thrust.add_LVLH_thrust_profile( + LVLH_thrust_direction, thrust_magnitude, t_thrust_start, t_thrust_end); + test_sat_thrust.add_LVLH_thrust_profile(LVLH_thrust_vec_2, t_thrust_2_start, + t_thrust_2_end); + + Satellite test_sat_torque("../tests/input_3.json"); + test_sat_torque.add_bodyframe_torque_profile( + torque_direction, torque_magnitude, t_torque_start, t_torque_end); + test_sat_torque.add_bodyframe_torque_profile(another_torque_vec, + t_torque_start, t_torque_end); + + Satellite test_sat_none_1("../tests/input_2.json"); + Satellite test_sat_none_2("../tests/input_3.json"); + + std::vector satellite_vector_1 = {test_sat_none_1, test_sat_none_2, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_2 = { + test_sat_none_1, test_sat_none_2, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + std::vector satellite_vector_3 = {test_sat_none_2, test_sat_none_1, + test_sat_thrust, test_sat_torque, + test_sat_both}; + std::vector satellite_vector_4 = { + test_sat_none_2, test_sat_none_1, test_sat_thrust, + test_sat_torque, test_sat_both, test_sat_none_2}; + + std::vector> satellite_vector_vector = { + satellite_vector_1, satellite_vector_2, satellite_vector_3, + satellite_vector_4}; + std::vector single_satellite_vec_1 = {test_sat_both}; + std::vector single_satellite_vec_2 = {test_sat_torque}; + satellite_vector_vector.push_back(single_satellite_vec_1); + satellite_vector_vector.push_back(single_satellite_vec_2); + sim_parameters.initial_timestep_guess = 2; + sim_parameters.total_sim_time = 300; + + // Drag parameters + sim_parameters.F_10 = 100; // Solar radio ten centimeter flux + sim_parameters.A_p = 120; // Geomagnetic A_p index + + double gs_latitude = 2; + double gs_longitude = 5; + double gs_altitude = 10; + double max_beam_angle_from_normal = 65; // deg + int num_beams = 2; + sim_parameters.total_sim_time = 25000; + PhasedArrayGroundStation example_ground_station_1( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); + + std::string file_name = "test_plot"; + std::vector orbital_elements = { + "Semimajor Axis", "Eccentricity", + "Inclination", "RAAN", + "Argument of Periapsis", "True Anomaly", + "Orbital Rate", "Orbital Angular Acceleration", + "Total Energy"}; + for (std::vector satellite_vector : satellite_vector_vector) { + for (std::string element_name : orbital_elements) { + sim_parameters.perturbation_bool = false; + sim_parameters.drag_bool = false; + sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, + satellite_vector, sim_parameters, + file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = false; + sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, + satellite_vector, sim_parameters, + file_name); + sim_parameters.perturbation_bool = true; + sim_parameters.drag_bool = true; + sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, + satellite_vector, sim_parameters, + file_name); } - + } } -TEST(UtilsTests,LowThrustTransferTest1) { - Satellite test_circular_sat("../tests/circular_orbit_test_2_input.json"); - double final_orbit_semimajor_axis = 12500; // km - double thrust_magnitude = 0.1; // N - double transfer_initiation_time = 10; // s - int error_code = add_lowthrust_orbit_transfer(test_circular_sat, final_orbit_semimajor_axis, - thrust_magnitude, transfer_initiation_time); - - EXPECT_TRUE(error_code == 0) << "Non-circular orbit flag got thrown incorrectly\n"; +TEST(UtilsTests, LowThrustTransferTest1) { + Satellite test_circular_sat("../tests/circular_orbit_test_2_input.json"); + double final_orbit_semimajor_axis = 12500; // km + double thrust_magnitude = 0.1; // N + double transfer_initiation_time = 10; // s + int error_code = add_lowthrust_orbit_transfer( + test_circular_sat, final_orbit_semimajor_axis, thrust_magnitude, + transfer_initiation_time); + + EXPECT_TRUE(error_code == 0) + << "Non-circular orbit flag got thrown incorrectly\n"; } -TEST(UtilsTests,LowThrustTransferTest2) { - Satellite test_circular_sat("../tests/elliptical_orbit_test_1.json"); - double final_orbit_semimajor_axis = 50000; // km - double thrust_magnitude = 0.1; // N - double transfer_initiation_time = 10; // s - int error_code = add_lowthrust_orbit_transfer(test_circular_sat, final_orbit_semimajor_axis, - thrust_magnitude, transfer_initiation_time); - - EXPECT_TRUE(error_code == 1) << "Non-circular orbit should have been thrown here\n"; +TEST(UtilsTests, LowThrustTransferTest2) { + Satellite test_circular_sat("../tests/elliptical_orbit_test_1.json"); + double final_orbit_semimajor_axis = 50000; // km + double thrust_magnitude = 0.1; // N + double transfer_initiation_time = 10; // s + int error_code = add_lowthrust_orbit_transfer( + test_circular_sat, final_orbit_semimajor_axis, thrust_magnitude, + transfer_initiation_time); + + EXPECT_TRUE(error_code == 1) + << "Non-circular orbit should have been thrown here\n"; } \ No newline at end of file From a717aad3ca35f1e6f4f73dcf0443c49057bb7c88 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 02:16:25 -0700 Subject: [PATCH 5/7] Running clang-format on simulation_setup file --- .gitignore | 3 +- simulation_setup.cpp | 129 +++++++++++++++++++++++++------------------ 2 files changed, 77 insertions(+), 55 deletions(-) diff --git a/.gitignore b/.gitignore index 2e78f26..354d850 100644 --- a/.gitignore +++ b/.gitignore @@ -4,4 +4,5 @@ build/ *.png src/files_to_format.txt include/files_to_format.txt -tests/files_to_format.txt \ No newline at end of file +tests/files_to_format.txt +files_to_format.txt \ No newline at end of file diff --git a/simulation_setup.cpp b/simulation_setup.cpp index 7cd5886..11bb419 100644 --- a/simulation_setup.cpp +++ b/simulation_setup.cpp @@ -1,13 +1,14 @@ #include +#include "PhasedArrayGroundStation.h" #include "Satellite.h" #include "utils.h" -#include "PhasedArrayGroundStation.h" int main() { // This file demonstrates a few different ways you can run and // visualize data from satellite simulations. - // First let's initialize the struct containing parameters for simulation and plotting + // First let's initialize the struct containing parameters for simulation and + // plotting SimParameters sim_parameters("../sim_parameters_example.json"); // Initialize satellite object from an input JSON file Satellite test_sat_1("../example_satellite_input_files/input.json"); @@ -59,8 +60,8 @@ int main() { t_torque_start, t_torque_end); std::vector satellite_vector_3 = {test_sat_7}; file_name = "Pitch Plot"; - sim_and_plot_attitude_evolution_gnuplot( - satellite_vector_3,sim_parameters, "Pitch", file_name); + sim_and_plot_attitude_evolution_gnuplot(satellite_vector_3, sim_parameters, + "Pitch", file_name); // Now let's demonstrate effect of atmospheric drag approximation Satellite test_sat_8("../example_satellite_input_files/input_8.json"); @@ -74,15 +75,14 @@ int main() { // Collect drag parameters into a tuple with F_10 first and A_p second std::pair drag_elements = {F_10, A_p}; sim_parameters.total_sim_time = 10000; - sim_parameters.epsilon = pow(10,-14); + sim_parameters.epsilon = pow(10, -14); sim_parameters.drag_bool = true; file_name = "Eccentricity Plot"; - sim_and_plot_orbital_elem_gnuplot(satellite_vector_4,sim_parameters, - "Eccentricity", file_name); + sim_and_plot_orbital_elem_gnuplot(satellite_vector_4, sim_parameters, + "Eccentricity", file_name); file_name = "Semimajor Axis"; - sim_and_plot_orbital_elem_gnuplot(satellite_vector_4, sim_parameters, - "Semimajor Axis",file_name); - + sim_and_plot_orbital_elem_gnuplot(satellite_vector_4, sim_parameters, + "Semimajor Axis", file_name); // Now demonstrating phased array ground station coverage Satellite test_sat_10("../example_satellite_input_files/input_10.json"); @@ -92,74 +92,95 @@ int main() { double gs_latitude = 2; double gs_longitude = 5; double gs_altitude = 10; - double max_beam_angle_from_normal = 65; //deg + double max_beam_angle_from_normal = 65; // deg int num_beams = 5; sim_parameters.total_sim_time = 40000; sim_parameters.perturbation_bool = true; - PhasedArrayGroundStation example_ground_station_1(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); - std::vector long_sat_vec = {test_sat_1,test_sat_2,test_sat_3,test_sat_10,test_sat_11,test_sat_12,test_sat_13}; - std::string coverage_file_name = "Ground station connectivity with " + std::to_string(num_beams) + " beams"; - sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, - long_sat_vec, sim_parameters, - coverage_file_name); - + PhasedArrayGroundStation example_ground_station_1( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); + std::vector long_sat_vec = {test_sat_1, test_sat_2, test_sat_3, + test_sat_10, test_sat_11, test_sat_12, + test_sat_13}; + std::string coverage_file_name = "Ground station connectivity with " + + std::to_string(num_beams) + " beams"; + sim_and_plot_gs_connectivity_gnuplot(example_ground_station_1, long_sat_vec, + sim_parameters, coverage_file_name); + num_beams = 2; - PhasedArrayGroundStation example_ground_station_2(gs_latitude,gs_longitude, - gs_altitude,max_beam_angle_from_normal,num_beams); - coverage_file_name = "Ground station connectivity with " + std::to_string(num_beams) + " beams"; - sim_and_plot_gs_connectivity_gnuplot(example_ground_station_2, - long_sat_vec, sim_parameters, - coverage_file_name); + PhasedArrayGroundStation example_ground_station_2( + gs_latitude, gs_longitude, gs_altitude, max_beam_angle_from_normal, + num_beams); + coverage_file_name = "Ground station connectivity with " + + std::to_string(num_beams) + " beams"; + sim_and_plot_gs_connectivity_gnuplot(example_ground_station_2, long_sat_vec, + sim_parameters, coverage_file_name); // Now demonstrating low-thrust orbital transfer - Satellite orbit_raising_demo_sat("../example_satellite_input_files/circular_orbit_raising_test_input.json"); - Satellite orbit_lowering_demo_sat("../example_satellite_input_files/circular_orbit_lowering_test_input.json"); - double raising_final_orbit_semimajor_axis = 20000; // km - thrust_magnitude = 1; // N - double transfer_initiation_time = 0; // s - int error_code_raising = add_lowthrust_orbit_transfer(orbit_raising_demo_sat, raising_final_orbit_semimajor_axis, + Satellite orbit_raising_demo_sat( + "../example_satellite_input_files/" + "circular_orbit_raising_test_input.json"); + Satellite orbit_lowering_demo_sat( + "../example_satellite_input_files/" + "circular_orbit_lowering_test_input.json"); + double raising_final_orbit_semimajor_axis = 20000; // km + thrust_magnitude = 1; // N + double transfer_initiation_time = 0; // s + int error_code_raising = add_lowthrust_orbit_transfer( + orbit_raising_demo_sat, raising_final_orbit_semimajor_axis, thrust_magnitude, transfer_initiation_time); - double lowering_final_orbit_semimajor_axis = 10000; // km - int error_code_lowering = add_lowthrust_orbit_transfer(orbit_lowering_demo_sat, lowering_final_orbit_semimajor_axis, - thrust_magnitude, transfer_initiation_time); - std::vector orbit_transfer_demo_vec = {orbit_raising_demo_sat,orbit_lowering_demo_sat}; + double lowering_final_orbit_semimajor_axis = 10000; // km + int error_code_lowering = add_lowthrust_orbit_transfer( + orbit_lowering_demo_sat, lowering_final_orbit_semimajor_axis, + thrust_magnitude, transfer_initiation_time); + std::vector orbit_transfer_demo_vec = {orbit_raising_demo_sat, + orbit_lowering_demo_sat}; sim_parameters.initial_timestep_guess = 2; sim_parameters.total_sim_time = 400000; sim_parameters.epsilon = pow(10, -12); sim_parameters.perturbation_bool = false; sim_parameters.drag_bool = false; // Axis tick increments to make axes less cluttered - sim_parameters.x_increment = pow(10,7); - sim_parameters.y_increment = pow(10,7); - sim_parameters.z_increment = 5*pow(10,6); + sim_parameters.x_increment = pow(10, 7); + sim_parameters.y_increment = pow(10, 7); + sim_parameters.z_increment = 5 * pow(10, 6); // file_name = "Semimajor axis transfer"; - // sim_and_plot_orbital_elem_gnuplot(orbit_transfer_demo_vec, sim_parameters, "Semimajor Axis", file_name); - sim_and_draw_orbit_gnuplot(orbit_transfer_demo_vec,sim_parameters); - + // sim_and_plot_orbital_elem_gnuplot(orbit_transfer_demo_vec, sim_parameters, + // "Semimajor Axis", file_name); + sim_and_draw_orbit_gnuplot(orbit_transfer_demo_vec, sim_parameters); // Now let's demonstrate changing the argument of periapsis - // Calibration strategy: there are some inherent oscillations in, e.g., arg of periapsis, even in absence of external forces or perturbations - // This oscillation magnitude can be different in initial and final orbits, so current strategy is to find the mean val of these oscillations - // at initial and final orbits, use those to get an offset, which can be applied to the final argument of periapsis to try to make the - // oscillations at the final orbit be close to the target value - - Satellite arg_periapsis_change_sat("../example_satellite_input_files/arg_of_periapsis_test_input.json"); - sim_parameters.epsilon = pow(10,-14); - sim_parameters.total_sim_time = 400000; + // Calibration strategy: there are some inherent oscillations in, e.g., arg of + // periapsis, even in absence of external forces or perturbations This + // oscillation magnitude can be different in initial and final orbits, so + // current strategy is to find the mean val of these oscillations at initial + // and final orbits, use those to get an offset, which can be applied to the + // final argument of periapsis to try to make the oscillations at the final + // orbit be close to the target value + + Satellite arg_periapsis_change_sat( + "../example_satellite_input_files/arg_of_periapsis_test_input.json"); + sim_parameters.epsilon = pow(10, -14); + sim_parameters.total_sim_time = 400000; sim_parameters.perturbation_bool = false; sim_parameters.drag_bool = false; t_thrust_start = 50000; double final_arg_of_periapsis_deg = 25; - thrust_magnitude = 0.1; // N - // std::cout << "orbital period: " << arg_periapsis_change_sat.calculate_orbital_period() << "\n"; - arg_periapsis_change_sat.add_maneuver("Argument of Periapsis Change",t_thrust_start,final_arg_of_periapsis_deg,thrust_magnitude); + thrust_magnitude = 0.1; // N + // std::cout << "orbital period: " << + // arg_periapsis_change_sat.calculate_orbital_period() << "\n"; + arg_periapsis_change_sat.add_maneuver( + "Argument of Periapsis Change", t_thrust_start, + final_arg_of_periapsis_deg, thrust_magnitude); file_name = "Arg of periapsis transfer"; - std::vector arg_of_periapsis_transfer_vec = {arg_periapsis_change_sat}; - sim_and_plot_orbital_elem_gnuplot(arg_of_periapsis_transfer_vec, sim_parameters, "Argument of Periapsis", file_name); + std::vector arg_of_periapsis_transfer_vec = { + arg_periapsis_change_sat}; + sim_and_plot_orbital_elem_gnuplot(arg_of_periapsis_transfer_vec, + sim_parameters, "Argument of Periapsis", + file_name); return 0; } \ No newline at end of file From 3cebe35a626074217e089eb9e52e4eab4e322494 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 02:52:03 -0700 Subject: [PATCH 6/7] Rerunning test coverage script --- tests/Satellite_tests.cpp | 4 +- ....cpp.b1467fc67cdaa758f7764df5452c5918.html | 669 +- ...on.h.5b54056581927049d160ff3354b9e6f1.html | 174 +- ....cpp.bef08eb3aaec087d7cd23d21b2ecdb00.html | 2657 ++++---- ...te.h.016907876294210b00a2d880adf10425.html | 1261 ++-- tests/test_coverage_detailed.functions.html | 181 +- tests/test_coverage_detailed.html | 64 +- ....cpp.4d3039dff574b788948119de402ca8d9.html | 5525 +++++++++-------- ...ls.h.0924fa377d356c0f9a6a386ccdf5fa6d.html | 1369 ++-- tests/test_coverage_summary.json | 2 +- 10 files changed, 6460 insertions(+), 5446 deletions(-) diff --git a/tests/Satellite_tests.cpp b/tests/Satellite_tests.cpp index 1633b55..00356b2 100644 --- a/tests/Satellite_tests.cpp +++ b/tests/Satellite_tests.cpp @@ -400,7 +400,7 @@ TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver1) { const double acceleration = thrust_magnitude / satellite_mass; const double maneuver_length = delta_V / acceleration; const double total_sim_time = maneuver_length + 10000; - double temp_epsilon = pow(10, -14); + double temp_epsilon = pow(10, -13); test_satellite.add_maneuver("Argument of Periapsis Change", t_thrust_start, target_arg_of_periapsis_deg, thrust_magnitude); double current_time = test_satellite.get_instantaneous_time(); @@ -455,7 +455,7 @@ TEST(EllipticalOrbitTests, ArgofPeriapsisChangeManeuver2) { const double acceleration = thrust_magnitude / satellite_mass; const double maneuver_length = delta_V / acceleration; const double total_sim_time = maneuver_length + 10000; - double temp_epsilon = pow(10, -14); + double temp_epsilon = pow(10, -13); test_satellite.add_maneuver("Argument of Periapsis Change", t_thrust_start, target_arg_of_periapsis_deg, thrust_magnitude); double current_time = test_satellite.get_instantaneous_time(); diff --git a/tests/test_coverage_detailed.PhasedArrayGroundStation.cpp.b1467fc67cdaa758f7764df5452c5918.html b/tests/test_coverage_detailed.PhasedArrayGroundStation.cpp.b1467fc67cdaa758f7764df5452c5918.html index 10c0b03..1843757 100644 --- a/tests/test_coverage_detailed.PhasedArrayGroundStation.cpp.b1467fc67cdaa758f7764df5452c5918.html +++ b/tests/test_coverage_detailed.PhasedArrayGroundStation.cpp.b1467fc67cdaa758f7764df5452c5918.html @@ -26,7 +26,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -40,8 +40,8 @@

GCC Code Coverage Report

Lines: - 74 - 75 + 78 + 79 98.7% @@ -70,12 +70,12 @@

GCC Code Coverage Report

Call count Block coverage - PhasedArrayGroundStation::angle_to_satellite_from_normal(Satellite) (line 34)called 8749080 times100.0% - PhasedArrayGroundStation::distance_to_satellite(Satellite) (line 18)called 4731363 times100.0% - PhasedArrayGroundStation::generate_ECEF_position() (line 9)called 5 times100.0% - PhasedArrayGroundStation::get_ECI_position(double) (line 13)called 13480446 times100.0% - PhasedArrayGroundStation::num_sats_connected_at_this_time(double) (line 70)called 8747784 times84.0% - PhasedArrayGroundStation::update_linked_sats_map(unsigned long, double, double) (line 112)called 714942 times77.0% + PhasedArrayGroundStation::angle_to_satellite_from_normal(Satellite) (line 39)called 8749080 times100.0% + PhasedArrayGroundStation::distance_to_satellite(Satellite) (line 20)called 4731363 times100.0% + PhasedArrayGroundStation::generate_ECEF_position() (line 11)called 5 times100.0% + PhasedArrayGroundStation::get_ECI_position(double) (line 15)called 13480446 times100.0% + PhasedArrayGroundStation::num_sats_connected_at_this_time(double) (line 79)called 8747784 times84.0% + PhasedArrayGroundStation::update_linked_sats_map(unsigned long, double, double) (line 124)called 714942 times77.0% @@ -94,14 +94,14 @@

GCC Code Coverage Report

- #include <cmath> + #include "PhasedArrayGroundStation.h" 2 - #include <iostream> + 3 @@ -115,14 +115,14 @@

GCC Code Coverage Report

- #include "PhasedArrayGroundStation.h" + #include <cmath> 5 - #include "utils.h" + #include <iostream> 6 @@ -136,7 +136,7 @@

GCC Code Coverage Report

- using Eigen::Vector3d; + #include "utils.h" 8 @@ -149,123 +149,151 @@

GCC Code Coverage Report

9 - 5 - void PhasedArrayGroundStation::generate_ECEF_position() { + + using Eigen::Vector3d; 10 - 5 - ECEF_position_ = convert_lat_long_to_ECEF(latitude, longitude, height); + + 11 5 - } + void PhasedArrayGroundStation::generate_ECEF_position() { 12 - - + 5 + ECEF_position_ = convert_lat_long_to_ECEF(latitude, longitude, height); 13 - 13480446 - Vector3d PhasedArrayGroundStation::get_ECI_position(double input_time) { + 5 + } 14 - 13480446 - Vector3d ECI_position_vec = convert_ECEF_to_ECI(ECEF_position_, input_time); + + 15 13480446 - return ECI_position_vec; + Vector3d PhasedArrayGroundStation::get_ECI_position(double input_time) { 16 - - } + 13480446 + Vector3d ECI_position_vec = convert_ECEF_to_ECI(ECEF_position_, input_time); 17 - - + 13480446 + return ECI_position_vec; 18 - 4731363 - double PhasedArrayGroundStation::distance_to_satellite(Satellite input_satellite) { + + } 19 - // Computes Euclidean distance to a satellite + 20 4731363 - std::array<double,3> satellite_position_ECI = input_satellite.get_ECI_position(); + double PhasedArrayGroundStation::distance_to_satellite( 21 - 4731363 - double current_time = input_satellite.get_instantaneous_time(); + + Satellite input_satellite) { 22 - 4731363 - Vector3d groundstation_position_ECI = get_ECI_position(current_time); + + // Computes Euclidean distance to a satellite 23 - + std::array<double, 3> satellite_position_ECI = 24 - - // Convert to Eigen Vector3d + 4731363 + input_satellite.get_ECI_position(); 25 4731363 - Vector3d satellite_position_vec; + double current_time = input_satellite.get_instantaneous_time(); 26 + + + 4731363 + Vector3d groundstation_position_ECI = get_ECI_position(current_time); + + + 27 + + + + + + + 28 + + + + // Convert to Eigen Vector3d + + + 29 + + + 4731363 + Vector3d satellite_position_vec; + + + 30
2/2 @@ -276,171 +304,192 @@

GCC Code Coverage Report

18925452 - for (size_t ind=0; ind<satellite_position_ECI.size();ind++) { + for (size_t ind = 0; ind < satellite_position_ECI.size(); ind++) { - 27 + 31 14194089 - satellite_position_vec(ind) = satellite_position_ECI.at(ind); + satellite_position_vec(ind) = satellite_position_ECI.at(ind); - 28 + 32 14194089 - } + } - 29 + 33 - // Order doesn't matter here + // Order doesn't matter here - 30 + 34 + + + + Vector3d difference_vec = + + + 35 4731363 - Vector3d difference_vec = (satellite_position_vec - groundstation_position_ECI); + (satellite_position_vec - groundstation_position_ECI); - 31 + 36 4731363 - return difference_vec.norm(); + return difference_vec.norm(); - 32 + 37 } - 33 + 38 - 34 + 39 8749080 - double PhasedArrayGroundStation::angle_to_satellite_from_normal(Satellite input_satellite) { + double PhasedArrayGroundStation::angle_to_satellite_from_normal( - 35 + 40 - + Satellite input_satellite) { - 36 + 41 - // Computes angle between vector pointing from ground station to satellite + // Computes angle between vector pointing from ground station to satellite - 37 + 42 - // and the vector normal to the ground station's antenna plane + // and the vector normal to the ground station's antenna plane - 38 + 43 - // Note: for now, this antenna plane is assumed to be tangential to the Earth + // Note: for now, this antenna plane is assumed to be tangential to the Earth - 39 + 44 - // at the antenna's location. + // at the antenna's location. - 40 + 45 - 41 + 46 - // Ref: https://archive.aoe.vt.edu/lutze/AOE4134/12SatelliteLookAngle.pdf + // Ref: https://archive.aoe.vt.edu/lutze/AOE4134/12SatelliteLookAngle.pdf - 42 + 47 - // but I don't think you need to use that topocentric-horizontal coordinate system + // but I don't think you need to use that topocentric-horizontal coordinate - 43 + 48 - // to just get angle between antenna plane normal and station-satellite vector + // system to just get angle between antenna plane normal and station-satellite - 44 + 49 + + + + // vector + + + 50 8749080 - double current_time = input_satellite.get_instantaneous_time(); + double current_time = input_satellite.get_instantaneous_time(); - 45 + 51 8749080 - Vector3d groundstation_position_ECI = get_ECI_position(current_time); + Vector3d groundstation_position_ECI = get_ECI_position(current_time); - 46 + 52 - 47 + 53 + + + + std::array<double, 3> satellite_position_ECI = + + + 54 8749080 - std::array<double,3> satellite_position_ECI = input_satellite.get_ECI_position(); + input_satellite.get_ECI_position(); - 48 + 55 - // Convert to Eigen Vector3d + // Convert to Eigen Vector3d - 49 + 56 8749080 - Vector3d satellite_position_vec; + Vector3d satellite_position_vec; - 50 + 57
2/2 @@ -451,199 +500,220 @@

GCC Code Coverage Report

34996320 - for (size_t ind=0; ind<satellite_position_ECI.size();ind++) { + for (size_t ind = 0; ind < satellite_position_ECI.size(); ind++) { - 51 + 58 26247240 - satellite_position_vec(ind) = satellite_position_ECI.at(ind); + satellite_position_vec(ind) = satellite_position_ECI.at(ind); - 52 + 59 26247240 - } + } - 53 + 60 - 54 + 61 + + + + Vector3d station_to_satellite_vec = + + + 62 8749080 - Vector3d station_to_satellite_vec = satellite_position_vec - groundstation_position_ECI; + satellite_position_vec - groundstation_position_ECI; - 55 + 63 - // Normalize to avoid needing magnitudes in angle calculation + // Normalize to avoid needing magnitudes in angle calculation - 56 + 64 - // So this is just a unit vector now + // So this is just a unit vector now - 57 + 65 8749080 - station_to_satellite_vec.normalize(); + station_to_satellite_vec.normalize(); - 58 + 66 - 59 + 67 - // Antenna plane normal is (given current assumptions) in the same + // Antenna plane normal is (given current assumptions) in the same - 60 + 68 - // direction as the vector from the center of the Earth to the ground station + // direction as the vector from the center of the Earth to the ground station - 61 + 69 8749080 - Vector3d antenna_plane_normal_direction = groundstation_position_ECI; + Vector3d antenna_plane_normal_direction = groundstation_position_ECI; - 62 + 70 8749080 - antenna_plane_normal_direction.normalize(); + antenna_plane_normal_direction.normalize(); - 63 + 71 - 64 + 72 - // See, e.g., https://www.wikihow.com/Find-the-Angle-Between-Two-Vectors + // See, e.g., https://www.wikihow.com/Find-the-Angle-Between-Two-Vectors - 65 + 73 8749080 - double angle_radians = acos(station_to_satellite_vec.dot(antenna_plane_normal_direction)); + double angle_radians = - 66 + 74 + + + 8749080 + acos(station_to_satellite_vec.dot(antenna_plane_normal_direction)); + + + 75 - // Make sure returned angle is in degrees + // Make sure returned angle is in degrees - 67 + 76 8749080 - return (angle_radians * (180/M_PI)); + return (angle_radians * (180 / M_PI)); - 68 + 77 } - 69 + 78 - 70 + 79 8747784 - int PhasedArrayGroundStation::num_sats_connected_at_this_time(double input_time) { + int PhasedArrayGroundStation::num_sats_connected_at_this_time( - 71 + 80 - // Goal: check the number of satellites whose time ranges of being linked with this ground station + double input_time) { - 72 + 81 - // include the current time + // Goal: check the number of satellites whose time ranges of being linked with - 73 + 82 + + + + // this ground station include the current time + + + 83 - 74 + 84 - // Method: two-pointer search along each element of linked_sats_list to find + // Method: two-pointer search along each element of linked_sats_list to find - 75 + 85 - // first and last ranges that overlap the input time + // first and last ranges that overlap the input time - 76 + 86 8747784 - int connected_sats = 0; + int connected_sats = 0; - 77 + 87 - 78 + 88
2/2 @@ -654,17 +724,24 @@

GCC Code Coverage Report

32237334 - for (auto key_val_pair : linked_sats_map_) { + for (auto key_val_pair : linked_sats_map_) { - 79 + 89 23489550 - size_t satellite_ind = key_val_pair.first; + size_t satellite_ind = key_val_pair.first; - 80 + 90 + + + + std::vector<std::pair<double, double>> satellite_comms_range_list = + + + 91
1/2 @@ -675,38 +752,38 @@

GCC Code Coverage Report

23489550 - std::vector<std::pair<double,double>> satellite_comms_range_list = key_val_pair.second; + key_val_pair.second; - 81 + 92 - // For a given satellite + // For a given satellite - 82 + 93 - // I just need to identify whether there exists a single range that encompasses the input time + // I just need to identify whether there exists a single range that - 83 + 94 - // I can do this by just finding the last range where the t_start <= input_time and + // encompasses the input time I can do this by just finding the last range - 84 + 95 - // see if t_end >= input_time + // where the t_start <= input_time and see if t_end >= input_time - 85 + 96
2/2 @@ -717,72 +794,84 @@

GCC Code Coverage Report

23489550 - if (satellite_comms_range_list.size() == 1) { + if (satellite_comms_range_list.size() == 1) { - 86 + 97
- 6/8 + 5/6
✓ Branch 0 taken 11951604 times.
✗ Branch 1 not taken.
✓ Branch 2 taken 7669368 times.
✓ Branch 3 taken 4282236 times.
-
✓ Branch 4 taken 7669368 times.
-
✗ Branch 5 not taken.
-
✓ Branch 6 taken 7050528 times.
-
✓ Branch 7 taken 618840 times.
+
✓ Branch 4 taken 7050528 times.
+
✓ Branch 5 taken 618840 times.
- 11951604 - if ((satellite_comms_range_list.at(0).first <= input_time) && (satellite_comms_range_list.at(0).second >= input_time)) { + 19620972 + if ((satellite_comms_range_list.at(0).first <= input_time) && - 87 + 98 + +
+ 1/2 +
+
✓ Branch 0 taken 7669368 times.
+
✗ Branch 1 not taken.
+
+
+ + 7669368 + (satellite_comms_range_list.at(0).second >= input_time)) { + + + 99 618840 - connected_sats += 1; + connected_sats += 1; - 88 + 100 618840 - continue; + continue; - 89 + 101 - } + } - 90 + 102 11332764 - } + } - 91 + 103 22870710 - int right_ind = satellite_comms_range_list.size() - 1; + int right_ind = satellite_comms_range_list.size() - 1; - 92 + 104 - int last_matching_pair_ind; + int last_matching_pair_ind; - 93 + 105
2/2 @@ -793,10 +882,17 @@

GCC Code Coverage Report

36855846 - while (right_ind >= 0) { + while (right_ind >= 0) { - 94 + 106 + + + + std::pair<double, double> right_range = + + + 107
1/2 @@ -807,10 +903,10 @@

GCC Code Coverage Report

29816406 - std::pair<double,double> right_range = satellite_comms_range_list.at(right_ind); + satellite_comms_range_list.at(right_ind); - 95 + 108
2/2 @@ -821,24 +917,24 @@

GCC Code Coverage Report

29816406 - if (right_range.second < input_time) { + if (right_range.second < input_time) { - 96 + 109 15013314 - break; + break; - 97 + 110 - } + } - 98 + 111
2/2 @@ -849,31 +945,24 @@

GCC Code Coverage Report

14803092 - if (right_range.first > input_time) { + if (right_range.first > input_time) { - 99 + 112 13985136 - right_ind -= 1; + right_ind -= 1; - 100 + 113 13985136 - } - - - 101 - - - - else { + } else { - 102 + 114
1/2 @@ -884,45 +973,45 @@

GCC Code Coverage Report

817956 - if (right_range.second >= input_time) { + if (right_range.second >= input_time) { - 103 + 115 817956 - connected_sats += 1; + connected_sats += 1; - 104 + 116 817956 - } + } - 105 + 117 817956 - break; + break; - 106 + 118 - } + } - 107 + 119 - } + } - 108 + 120
4/5 @@ -936,52 +1025,66 @@

GCC Code Coverage Report

23489550 - } + } - 109 + 121 8747784 - return connected_sats; + return connected_sats; - 110 + 122} - 111 + 123 - 112 + 124 714942 - void PhasedArrayGroundStation::update_linked_sats_map(const size_t satellite_index, const double connection_time, const double previous_time) { + void PhasedArrayGroundStation::update_linked_sats_map( - 113 + 125 - // If you're just extending an existing range, update the t_end of existing pair, + const size_t satellite_index, const double connection_time, - 114 + 126 - // otherwise create a new pair with the current time as the t_start + const double previous_time) { - 115 + 127 + + + + // If you're just extending an existing range, update the t_end of existing + + + 128 + + + + // pair, otherwise create a new pair with the current time as the t_start + + + 129
2/2 @@ -992,24 +1095,31 @@

GCC Code Coverage Report

714942 - if (linked_sats_map_.count(satellite_index) == 0) { + if (linked_sats_map_.count(satellite_index) == 0) { - 116 + 130 1296 - std::pair<double,double> connection_time_range = {connection_time,connection_time}; + std::pair<double, double> connection_time_range = {connection_time, - 117 + 131 + + + + connection_time}; + + + 132 1296 - std::vector<std::pair<double,double>> tmp_vector = {connection_time_range}; + std::vector<std::pair<double, double>> tmp_vector = {connection_time_range}; - 118 + 133
1/2 @@ -1020,45 +1130,45 @@

GCC Code Coverage Report

1296 - linked_sats_map_.emplace(satellite_index,tmp_vector); + linked_sats_map_.emplace(satellite_index, tmp_vector); - 119 + 134 1296 - } + } else { - 120 + 135 - else { + // Look at most recently added range - 121 + 136 - + std::vector<std::pair<double, double>> existing_connection_time_ranges = - 122 + 137 - - // Look at most recently added range + 713646 + linked_sats_map_[satellite_index]; - 123 + 138 - 713646 - std::vector<std::pair<double,double>> existing_connection_time_ranges = linked_sats_map_[satellite_index]; + + std::pair<double, double> most_recent_range = - 124 + 139
1/2 @@ -1069,10 +1179,17 @@

GCC Code Coverage Report

713646 - std::pair<double,double> most_recent_range = existing_connection_time_ranges.at(existing_connection_time_ranges.size() - 1); + existing_connection_time_ranges.at( - 125 + 140 + + + 713646 + existing_connection_time_ranges.size() - 1); + + + 141
2/2 @@ -1083,24 +1200,24 @@

GCC Code Coverage Report

713646 - if (most_recent_range.second == previous_time) { + if (most_recent_range.second == previous_time) { - 126 + 142 - // Just extending existing range + // Just extending existing range - 127 + 143 712872 - most_recent_range.second = connection_time; + most_recent_range.second = connection_time; - 128 + 144
1/2 @@ -1111,10 +1228,17 @@

GCC Code Coverage Report

712872 - existing_connection_time_ranges.at(existing_connection_time_ranges.size() - 1) = most_recent_range; + existing_connection_time_ranges.at( - 129 + 145 + + + 712872 + existing_connection_time_ranges.size() - 1) = most_recent_range; + + + 146
2/4 @@ -1127,31 +1251,31 @@

GCC Code Coverage Report

712872 - linked_sats_map_[satellite_index] = existing_connection_time_ranges; + linked_sats_map_[satellite_index] = existing_connection_time_ranges; - 130 + 147 712872 - } + } else { - 131 + 148 - else { + // New connection range - 132 + 149 - // New connection range + std::vector<std::pair<double, double>> existing_connection_time_ranges = - 133 + 150
2/4 @@ -1164,17 +1288,24 @@

GCC Code Coverage Report

774 - std::vector<std::pair<double,double>> existing_connection_time_ranges = linked_sats_map_[satellite_index]; + linked_sats_map_[satellite_index]; - 134 + 151 774 - std::pair<double,double> new_connection_time_range = {connection_time,connection_time}; + std::pair<double, double> new_connection_time_range = {connection_time, - 135 + 152 + + + + connection_time}; + + + 153
1/2 @@ -1185,10 +1316,10 @@

GCC Code Coverage Report

774 - existing_connection_time_ranges.push_back(new_connection_time_range); + existing_connection_time_ranges.push_back(new_connection_time_range); - 136 + 154
2/4 @@ -1201,31 +1332,31 @@

GCC Code Coverage Report

774 - linked_sats_map_[satellite_index] = existing_connection_time_ranges; + linked_sats_map_[satellite_index] = existing_connection_time_ranges; - 137 + 155 774 - } + } - 138 + 156 713646 - } + } - 139 + 157 714942 } - 140 + 158 diff --git a/tests/test_coverage_detailed.PhasedArrayGroundStation.h.5b54056581927049d160ff3354b9e6f1.html b/tests/test_coverage_detailed.PhasedArrayGroundStation.h.5b54056581927049d160ff3354b9e6f1.html index 50f909a..b381331 100644 --- a/tests/test_coverage_detailed.PhasedArrayGroundStation.h.5b54056581927049d160ff3354b9e6f1.html +++ b/tests/test_coverage_detailed.PhasedArrayGroundStation.h.5b54056581927049d160ff3354b9e6f1.html @@ -26,7 +26,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -40,8 +40,8 @@

GCC Code Coverage Report

Lines: - 10 - 10 + 11 + 11 100.0% @@ -70,9 +70,9 @@

GCC Code Coverage Report

Call count Block coverage - PhasedArrayGroundStation::PhasedArrayGroundStation(PhasedArrayGroundStation const&) (line 11)called 648 times100.0% - PhasedArrayGroundStation::PhasedArrayGroundStation(double, double, double, double, int) (line 28)called 10 times100.0% - PhasedArrayGroundStation::~PhasedArrayGroundStation() (line 11)called 658 times100.0% + PhasedArrayGroundStation::PhasedArrayGroundStation(PhasedArrayGroundStation const&) (line 12)called 648 times100.0% + PhasedArrayGroundStation::PhasedArrayGroundStation(double, double, double, double, int) (line 32)called 10 times100.0% + PhasedArrayGroundStation::~PhasedArrayGroundStation() (line 12)called 658 times100.0% @@ -112,14 +112,14 @@

GCC Code Coverage Report

- #include <iostream> + #include <Eigen/Dense> 5 - #include <Eigen/Dense> + #include <iostream> 6 @@ -133,157 +133,199 @@

GCC Code Coverage Report

- #include "Satellite.h" + 8 - + #include "Satellite.h" 9 - using Eigen::Vector3d; + 10 - + using Eigen::Vector3d; 11 - class PhasedArrayGroundStation { + 12 - // Phased array ground station class + class PhasedArrayGroundStation { 13 - public: + // Phased array ground station class 14 - 5 - double latitude = {0}; + + public: 15 5 - double longitude = {0}; + double latitude = {0}; 16 5 - double height = {0}; + double longitude = {0}; 17 - - Vector3d ECEF_position_; + 5 + double height = {0}; 18 - 5 - double max_beam_angle_from_normal_ = {0}; //deg + + Vector3d ECEF_position_; 19 5 - int num_beams_ = {0}; + double max_beam_angle_from_normal_ = {0}; // deg 20 - - // To enforce the maximum number of satellites a ground station can communicate with at any one time, + 5 + int num_beams_ = {0}; 21 - // going to create a map where each key is the satellite index of a given satellite (i.e., index in a satellite vector being plotted) + // To enforce the maximum number of satellites a ground station can 22 - // Each key has a val which is a vector of pairs, where the first element is the start of a time range where the + // communicate with at any one time, going to create a map where each key is 23 - // ground station is communicating with that satellite, and the second element is the end time for that range + // the satellite index of a given satellite (i.e., index in a satellite vector 24 - // So communications with satellites are characterized by vectors of time ranges + // being plotted) Each key has a val which is a vector of pairs, where the 25 - + // first element is the start of a time range where the ground station is 26 - std::map<size_t,std::vector<std::pair<double,double>>> linked_sats_map_; + // communicating with that satellite, and the second element is the end time 27 - + // for that range So communications with satellites are characterized by 28 - 20 - PhasedArrayGroundStation(double latitude, double longitude, double height, double max_beam_angle_from_normal, int num_beams = 1) { + + // vectors of time ranges 29 + + + + + + + 30 + + + + std::map<size_t, std::vector<std::pair<double, double>>> linked_sats_map_; + + + 31 + + + + + + + 32 + + + 20 + PhasedArrayGroundStation(double latitude, double longitude, double height, + + + 33 + + + + double max_beam_angle_from_normal, + + + 34 + + + 5 + int num_beams = 1) { + + + 35
1/2 @@ -294,94 +336,108 @@

GCC Code Coverage Report

5 - generate_ECEF_position(); + generate_ECEF_position(); - 30 + 36 5 - num_beams_ = num_beams; + num_beams_ = num_beams; - 31 + 37 5 - max_beam_angle_from_normal_ = max_beam_angle_from_normal; + max_beam_angle_from_normal_ = max_beam_angle_from_normal; - 32 + 38 10 - } + } - 33 + 39 - void generate_ECEF_position(); + void generate_ECEF_position(); - 34 + 40 - Vector3d get_ECI_position(double input_time); + Vector3d get_ECI_position(double input_time); - 35 + 41 - double distance_to_satellite(Satellite input_satellite); + double distance_to_satellite(Satellite input_satellite); - 36 + 42 - double angle_to_satellite_from_normal(Satellite input_satellite); + double angle_to_satellite_from_normal(Satellite input_satellite); - 37 + 43 - int num_sats_connected_at_this_time(double input_time); + int num_sats_connected_at_this_time(double input_time); - 38 + 44 - void update_linked_sats_map(const size_t satellite_index, const double connection_time, const double previous_time); + void update_linked_sats_map(const size_t satellite_index, - 39 + 45 - }; + const double connection_time, - 40 + 46 + + + + const double previous_time); + + + 47 + + + + }; + + + 48 - 41 + 49 #endif - 42 + 50 diff --git a/tests/test_coverage_detailed.Satellite.cpp.bef08eb3aaec087d7cd23d21b2ecdb00.html b/tests/test_coverage_detailed.Satellite.cpp.bef08eb3aaec087d7cd23d21b2ecdb00.html index 70aa3ad..528a60e 100644 --- a/tests/test_coverage_detailed.Satellite.cpp.bef08eb3aaec087d7cd23d21b2ecdb00.html +++ b/tests/test_coverage_detailed.Satellite.cpp.bef08eb3aaec087d7cd23d21b2ecdb00.html @@ -26,7 +26,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -40,21 +40,21 @@

GCC Code Coverage Report

Lines: - 365 - 388 - 94.1% + 406 + 425 + 95.5% Functions: - 19 - 20 - 95.0% + 21 + 22 + 95.5% Branches: - 87 - 108 - 80.6% + 104 + 130 + 80.0% @@ -70,26 +70,28 @@

GCC Code Coverage Report

Call count Block coverage - Satellite::add_LVLH_thrust_profile(double, double, double) (line 280)not called0.0% - Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double) (line 240)called 10 times100.0% - Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double, double) (line 255)called 12 times100.0% - Satellite::add_arg_of_periapsis_change_thrust() (line 687)called 8948009 times70.0% - Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double) (line 561)called 10 times100.0% - Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double, double) (line 574)called 10 times85.0% - Satellite::calculate_instantaneous_orbit_angular_acceleration() (line 615)called 8948064 times100.0% - Satellite::calculate_instantaneous_orbit_rate() (line 595)called 8948064 times100.0% - Satellite::calculate_orbital_period() (line 18)called 56 times100.0% - Satellite::calculate_perifocal_position() (line 25)called 55 times100.0% - Satellite::calculate_perifocal_velocity() (line 44)called 55 times100.0% - Satellite::convert_ECI_to_perifocal(std::__1::array<double, 3ul>) (line 111)called 53688054 times100.0% - Satellite::convert_perifocal_to_ECI(std::__1::array<double, 3ul>) (line 61)called 110 times100.0% - Satellite::evolve_RK45(double, double, bool, bool, std::__1::pair<double, double>) (line 394)called 8948009 times82.0% - Satellite::get_attitude_val(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 652)called 96215 times84.0% - Satellite::get_orbital_elements() (line 383)called 9 times100.0% - Satellite::get_orbital_parameter(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 536)called 95664 times82.0% - Satellite::initialize_and_normalize_body_quaternion(double, double, double) (line 641)called 57 times100.0% - Satellite::initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame() (line 678)called 55 times100.0% - Satellite::update_orbital_elements_from_position_and_velocity() (line 287)called 8948011 times81.0% + Satellite::add_LVLH_thrust_profile(double, double, double) (line 289)not called0.0% + Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double) (line 249)called 10 times100.0% + Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double, double) (line 264)called 3495723 times100.0% + Satellite::add_arg_of_periapsis_change_thrust() (line 710)called 12466918 times100.0% + Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double) (line 581)called 10 times100.0% + Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double, double) (line 594)called 10 times85.0% + Satellite::add_maneuver(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, double, double, double) (line 758)called 2 times50.0% + Satellite::calculate_instantaneous_orbit_angular_acceleration() (line 635)called 12466975 times100.0% + Satellite::calculate_instantaneous_orbit_rate() (line 615)called 12466975 times100.0% + Satellite::calculate_orbital_period() (line 18)called 58 times100.0% + Satellite::calculate_perifocal_position() (line 25)called 57 times100.0% + Satellite::calculate_perifocal_velocity() (line 44)called 57 times100.0% + Satellite::check_for_maneuvers_to_initialize() (line 734)called 12466918 times87.0% + Satellite::convert_ECI_to_perifocal(std::__1::array<double, 3ul>) (line 112)called 74801508 times100.0% + Satellite::convert_perifocal_to_ECI(std::__1::array<double, 3ul>) (line 62)called 114 times100.0% + Satellite::evolve_RK45(double, double, bool, bool, std::__1::pair<double, double>) (line 406)called 12466918 times84.0% + Satellite::get_attitude_val(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 672)called 96215 times84.0% + Satellite::get_orbital_elements() (line 395)called 9 times100.0% + Satellite::get_orbital_parameter(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 555)called 95672 times82.0% + Satellite::initialize_and_normalize_body_quaternion(double, double, double) (line 661)called 59 times100.0% + Satellite::initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame() (line 701)called 57 times100.0% + Satellite::update_orbital_elements_from_position_and_velocity() (line 298)called 12466920 times81.0% @@ -226,7 +228,7 @@

GCC Code Coverage Report

18 - 56 + 58 double Satellite::calculate_orbital_period() { @@ -240,14 +242,14 @@

GCC Code Coverage Report

20 - 56 + 58 double T = 2 * M_PI * sqrt(pow(a_, 3) / (G * mass_Earth)); 21 - 56 + 58 return T; @@ -275,7 +277,7 @@

GCC Code Coverage Report

25 - 55 + 57 std::array<double, 3> Satellite::calculate_perifocal_position() { @@ -296,14 +298,14 @@

GCC Code Coverage Report

28 - 55 + 57 double p = 29 - 55 + 57 a_ * (1 - eccentricity_) * (1 + eccentricity_); // rearranging eq. 1-47 @@ -317,7 +319,7 @@

GCC Code Coverage Report

31 - 55 + 57 double r = p / (1 + eccentricity_ * cos(true_anomaly_)); @@ -331,14 +333,14 @@

GCC Code Coverage Report

33 - 55 + 57 double r_perifocal_P = r * cos(true_anomaly_); 34 - 55 + 57 double r_perifocal_Q = r * sin(true_anomaly_); @@ -352,21 +354,21 @@

GCC Code Coverage Report

36 - 55 + 57 calculated_perifocal_position.at(0) = r_perifocal_P; 37 - 55 + 57 calculated_perifocal_position.at(1) = r_perifocal_Q; 38 - 55 + 57 calculated_perifocal_position.at(2) = 0; // W component is 0 @@ -380,7 +382,7 @@

GCC Code Coverage Report

40 - 55 + 57 return calculated_perifocal_position; @@ -408,7 +410,7 @@

GCC Code Coverage Report

44 - 55 + 57 std::array<double, 3> Satellite::calculate_perifocal_velocity() { @@ -429,939 +431,939 @@

GCC Code Coverage Report

47 - 55 + 57 double p = 48 - 55 + 57 a_ * (1 - eccentricity_) * (1 + eccentricity_); // rearranging eq. 1-47 49 - 55 - const double mu_Earth = G*mass_Earth; + 57 + const double mu_Earth = G * mass_Earth; 50 - 55 + 57 double v_perifocal_P = sqrt(mu_Earth / p) * (-sin(true_anomaly_)); 51 - 55 - double v_perifocal_Q = sqrt(mu_Earth / p) * (eccentricity_ + cos(true_anomaly_)); + 57 + double v_perifocal_Q = 52 + 57 + sqrt(mu_Earth / p) * (eccentricity_ + cos(true_anomaly_)); + + + 53 + + - 53 + 54 - 55 + 57 calculated_perifocal_velocity.at(0) = v_perifocal_P; - 54 + 55 - 55 + 57 calculated_perifocal_velocity.at(1) = v_perifocal_Q; - 55 + 56 - 55 + 57 calculated_perifocal_velocity.at(2) = 0; // 0 component in the W direction - 56 + 57 - 57 + 58 - 55 + 57 return calculated_perifocal_velocity; - 58 + 59 } - 59 + 60 - 60 + 61 // Objective: convert a vector from perifocal frame to ECI coordinates - 61 + 62 - 110 + 114 std::array<double, 3> Satellite::convert_perifocal_to_ECI( - 62 + 63 const std::array<double, 3> input_perifocal_vec) { - 63 + 64 // Method from Fundamentals of Astrodynamics - 64 + 65 // Sounds like what they describe as their "Geocentric-Equatorial" coordinate - 65 + 66 // system is ECI - 66 + 67 - 110 + 114 Matrix3d R_tilde_matrix; - 67 + 68 - 68 + 69 - 110 + 114 R_tilde_matrix(0, 0) = - 69 + 70 - 220 + 228 cos(raan_) * cos(arg_of_periapsis_) - - 70 + 71 - 110 + 114 sin(raan_) * sin(arg_of_periapsis_) * cos(inclination_); - 71 + 72 - 72 + 73 - 110 + 114 R_tilde_matrix(0, 1) = - 73 + 74 - 220 + 228 -cos(raan_) * sin(arg_of_periapsis_) - - 74 + 75 - 110 + 114 sin(raan_) * cos(arg_of_periapsis_) * cos(inclination_); - 75 + 76 - 76 + 77 - 110 + 114 R_tilde_matrix(0, 2) = sin(raan_) * sin(inclination_); - 77 + 78 - 78 + 79 - 110 + 114 R_tilde_matrix(1, 0) = - 79 + 80 - 220 + 228 sin(raan_) * cos(arg_of_periapsis_) + - 80 + 81 - 110 + 114 cos(raan_) * sin(arg_of_periapsis_) * cos(inclination_); - 81 + 82 - 82 + 83 - 110 + 114 R_tilde_matrix(1, 1) = - 83 + 84 - 220 + 228 -sin(raan_) * sin(arg_of_periapsis_) + - 84 + 85 - 110 + 114 cos(raan_) * cos(arg_of_periapsis_) * cos(inclination_); - 85 + 86 - 86 + 87 - 110 + 114 R_tilde_matrix(1, 2) = -cos(raan_) * sin(inclination_); - 87 + 88 - 88 + 89 - 110 + 114 R_tilde_matrix(2, 0) = sin(arg_of_periapsis_) * sin(inclination_); - 89 + 90 - 90 + 91 - 110 + 114 R_tilde_matrix(2, 1) = cos(arg_of_periapsis_) * sin(inclination_); - 91 + 92 - 92 + 93 - 110 + 114 R_tilde_matrix(2, 2) = cos(inclination_); - 93 + 94 - 94 + 95 // convert to Eigen vectors just to make sure matrix-vector multiplication is - 95 + 96 // done correctly - 96 + 97 - 110 + 114 Vector3d vector_ijk(0, 0, 0); - 97 + 98 - 110 + 114 Vector3d vector_pqw(0, 0, 0); - 98 + 99 - 99 + 100 - 110 + 114 vector_pqw(0) = input_perifocal_vec.at(0); - 100 + 101 - 110 + 114 vector_pqw(1) = input_perifocal_vec.at(1); - 101 + 102 - 110 + 114 vector_pqw(2) = input_perifocal_vec.at(2); - 102 + 103 - 103 + 104 - 110 + 114 vector_ijk = R_tilde_matrix * vector_pqw; - 104 + 105 - 220 + 228 std::array<double, 3> output_vector_ijk = {vector_ijk(0), vector_ijk(1), - 105 + 106 - 110 + 114 vector_ijk(2)}; - 106 + 107 - 107 + 108 - 110 + 114 return output_vector_ijk; - 108 + 109 } - 109 + 110 - 110 + 111 // Objective: convert vector from ECI frame to perifocal frame - 111 + 112 - 53688054 + 74801508 std::array<double, 3> Satellite::convert_ECI_to_perifocal( - 112 + 113 const std::array<double, 3> input_ECI_vec) { - 113 + 114 // Method from Fundamentals of Astrodynamics, and using - 114 + 115 // https://en.wikipedia.org/wiki/Perifocal_coordinate_system Sounds like what - 115 + 116 // they describe as their "Geocentric-Equatorial" coordinate system is ECI - 116 + 117 - 53688054 + 74801508 Matrix3d R_tilde_matrix; - 117 + 118 - 118 + 119 - 53688054 + 74801508 R_tilde_matrix(0, 0) = - 119 + 120 - 107376108 + 149603016 cos(raan_) * cos(arg_of_periapsis_) - - 120 + 121 - 53688054 + 74801508 sin(raan_) * sin(arg_of_periapsis_) * cos(inclination_); - 121 + 122 - 122 + 123 - 53688054 + 74801508 R_tilde_matrix(0, 1) = - 123 + 124 - 107376108 + 149603016 -cos(raan_) * sin(arg_of_periapsis_) - - 124 + 125 - 53688054 + 74801508 sin(raan_) * cos(arg_of_periapsis_) * cos(inclination_); - 125 + 126 - 126 + 127 - 53688054 + 74801508 R_tilde_matrix(0, 2) = sin(raan_) * sin(inclination_); - 127 + 128 - 128 + 129 - 53688054 + 74801508 R_tilde_matrix(1, 0) = - 129 + 130 - 107376108 + 149603016 sin(raan_) * cos(arg_of_periapsis_) + - 130 + 131 - 53688054 + 74801508 cos(raan_) * sin(arg_of_periapsis_) * cos(inclination_); - 131 + 132 - 132 + 133 - 53688054 + 74801508 R_tilde_matrix(1, 1) = - 133 + 134 - 107376108 + 149603016 -sin(raan_) * sin(arg_of_periapsis_) + - 134 + 135 - 53688054 + 74801508 cos(raan_) * cos(arg_of_periapsis_) * cos(inclination_); - 135 + 136 - 136 + 137 - 53688054 + 74801508 R_tilde_matrix(1, 2) = -cos(raan_) * sin(inclination_); - 137 + 138 - 138 + 139 - 53688054 + 74801508 R_tilde_matrix(2, 0) = sin(arg_of_periapsis_) * sin(inclination_); - 139 + 140 - 140 + 141 - 53688054 + 74801508 R_tilde_matrix(2, 1) = cos(arg_of_periapsis_) * sin(inclination_); - 141 + 142 - 142 + 143 - 53688054 + 74801508 R_tilde_matrix(2, 2) = cos(inclination_); - 143 + 144 - 144 + 145 // convert to Eigen vectors just to make sure matrix-vector multiplication is - 145 + 146 // done correctly - 146 + 147 - 53688054 + 74801508 Vector3d vector_ijk(0, 0, 0); - 147 + 148 - 53688054 + 74801508 Vector3d vector_pqw(0, 0, 0); - 148 + 149 - 53688054 + 74801508 vector_ijk(0) = input_ECI_vec.at(0); - 149 + 150 - 53688054 + 74801508 vector_ijk(1) = input_ECI_vec.at(1); - 150 + 151 - 53688054 + 74801508 vector_ijk(2) = input_ECI_vec.at(2); - 151 + 152 - 152 + 153 - 53688054 + 74801508 vector_pqw = (R_tilde_matrix.inverse()) * vector_ijk; - 153 + 154 - 107376108 + 149603016 std::array<double, 3> output_vector_pqw = {vector_pqw(0), vector_pqw(1), - 154 + 155 - 53688054 + 74801508 vector_pqw(2)}; - 155 + 156 - 156 + 157 - 53688054 + 74801508 return output_vector_pqw; - 157 + 158 } - 158 + 159 - 159 + 160 // Objective: evolve position and velocity (combined into one vector) one - 160 + 161 // timestep via RK4 method - 161 + 162 // void Satellite::evolve_RK4(const double input_step_size) { - 162 + 163 // // format input position and velocity arrays into single array for RK4 step - 163 + 164 // std::array<double, 6> combined_initial_position_and_velocity_array = {}; - 164 + 165 // std::pair<std::array<double, 3>, std::array<double, 3>> - 165 + 166 // output_position_velocity_pair = {}; - 166 + 167 - 167 + 168 // for (size_t ind = 0; ind < 3; ind++) { - - 168 - - - - // combined_initial_position_and_velocity_array.at(ind) = - 169 - // ECI_position_.at(ind); + // combined_initial_position_and_velocity_array.at(ind) = 170 - // } + // ECI_position_.at(ind); 171 - // for (size_t ind = 3; ind < 6; ind++) { + // } 172 - // combined_initial_position_and_velocity_array.at(ind) = + // for (size_t ind = 3; ind < 6; ind++) { 173 - // ECI_velocity_.at(ind - 3); + // combined_initial_position_and_velocity_array.at(ind) = 174 - // } + // ECI_velocity_.at(ind - 3); 175 - + // } 176 - // // populate list of thrust forces at half a timestep past, for RK4 + 177 - // // calculations + // // populate list of thrust forces at half a timestep past, for RK4 178 - // std::vector<std::array<double, 3>> list_of_LVLH_forces_at_half_timestep_past = + // // calculations 179 - // {}; + // std::vector<std::array<double, 3>> 180 - // std::vector<std::array<double, 3>> list_of_ECI_forces_at_half_timestep_past = + // list_of_LVLH_forces_at_half_timestep_past = 181 @@ -1375,451 +1377,514 @@

GCC Code Coverage Report

- + // std::vector<std::array<double, 3>> list_of_ECI_forces_at_half_timestep_past 183 - // for (const ThrustProfileLVLH thrust_profile : thrust_profile_list_) { + // = 184 - // if (((t_ + (input_step_size / 2.0)) >= thrust_profile.t_start_) && + // {}; 185 - // ((t_ + (input_step_size / 2.0)) <= thrust_profile.t_end_)) { + 186 - // list_of_LVLH_forces_at_half_timestep_past.push_back( + // for (const ThrustProfileLVLH thrust_profile : thrust_profile_list_) { 187 - // thrust_profile.LVLH_force_vec_); + // if (((t_ + (input_step_size / 2.0)) >= thrust_profile.t_start_) && 188 - // std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( + // ((t_ + (input_step_size / 2.0)) <= thrust_profile.t_end_)) { 189 - // thrust_profile.LVLH_force_vec_, ECI_position_, ECI_velocity_); + // list_of_LVLH_forces_at_half_timestep_past.push_back( 190 - // list_of_ECI_forces_at_half_timestep_past.push_back(ECI_thrust_vector); + // thrust_profile.LVLH_force_vec_); 191 - // } + // std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( 192 - // } + // thrust_profile.LVLH_force_vec_, ECI_position_, ECI_velocity_); 193 - + // list_of_ECI_forces_at_half_timestep_past.push_back(ECI_thrust_vector); 194 - // // populate list of thrust forces at a timestep past, for RK4 calculations + // } 195 - // std::vector<std::array<double, 3>> list_of_LVLH_forces_at_one_timestep_past = + // } 196 - // {}; + 197 - // std::vector<std::array<double, 3>> list_of_ECI_forces_at_one_timestep_past = + // // populate list of thrust forces at a timestep past, for RK4 calculations 198 - // {}; + // std::vector<std::array<double, 3>> list_of_LVLH_forces_at_one_timestep_past 199 - + // = 200 - // for (const ThrustProfileLVLH thrust_profile : thrust_profile_list_) { + // {}; 201 - // if (((t_ + input_step_size) >= thrust_profile.t_start_) && + // std::vector<std::array<double, 3>> list_of_ECI_forces_at_one_timestep_past 202 - // ((t_ + input_step_size) <= thrust_profile.t_end_)) { + // = 203 - // list_of_LVLH_forces_at_one_timestep_past.push_back( + // {}; 204 - // thrust_profile.LVLH_force_vec_); + 205 - // std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( + // for (const ThrustProfileLVLH thrust_profile : thrust_profile_list_) { 206 - // thrust_profile.LVLH_force_vec_, ECI_position_, ECI_velocity_); + // if (((t_ + input_step_size) >= thrust_profile.t_start_) && 207 - // list_of_ECI_forces_at_one_timestep_past.push_back(ECI_thrust_vector); + // ((t_ + input_step_size) <= thrust_profile.t_end_)) { 208 - // } + // list_of_LVLH_forces_at_one_timestep_past.push_back( 209 - // } + // thrust_profile.LVLH_force_vec_); 210 - + // std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( 211 - // std::array<double, 6> output_combined_position_and_velocity_array = + // thrust_profile.LVLH_force_vec_, ECI_position_, ECI_velocity_); 212 - // RK4_step<6>(combined_initial_position_and_velocity_array, input_step_size, + // list_of_ECI_forces_at_one_timestep_past.push_back(ECI_thrust_vector); 213 - // RK4_deriv_function_orbit_position_and_velocity, m_, + // } 214 - // list_of_ECI_forces_at_this_time_, + // } 215 - // list_of_ECI_forces_at_half_timestep_past, + 216 - // list_of_ECI_forces_at_one_timestep_past); + // std::array<double, 6> output_combined_position_and_velocity_array = 217 - // // std::array<double,6> output_combined_angular_array= + // RK4_step<6>(combined_initial_position_and_velocity_array, 218 - // // RK4_step<6>(combined_initial_angular_array,input_step_size,RK4_deriv_function_angular,I_,list_of_body_frame_torques_at_this_time_,list_of_body_frame_torques_at_half_timestep_past,list_of_body_frame_torques_at_one_timestep_past); + // input_step_size, 219 - + // RK4_deriv_function_orbit_position_and_velocity, m_, 220 - // for (size_t ind = 0; ind < 3; ind++) { + // list_of_ECI_forces_at_this_time_, 221 - // ECI_position_.at(ind) = output_combined_position_and_velocity_array.at(ind); + // list_of_ECI_forces_at_half_timestep_past, 222 - // ECI_velocity_.at(ind) = + // list_of_ECI_forces_at_one_timestep_past); 223 - // output_combined_position_and_velocity_array.at(ind + 3); + // // std::array<double,6> output_combined_angular_array= 224 - // // also update the perifocal versions + // // 225 - // perifocal_position_ = convert_ECI_to_perifocal(ECI_position_); + // RK4_step<6>(combined_initial_angular_array,input_step_size,RK4_deriv_function_angular,I_,list_of_body_frame_torques_at_this_time_,list_of_body_frame_torques_at_half_timestep_past,list_of_body_frame_torques_at_one_timestep_past); 226 - // perifocal_velocity_ = convert_ECI_to_perifocal(ECI_velocity_); + 227 - // } + // for (size_t ind = 0; ind < 3; ind++) { 228 - // t_ += input_step_size; + // ECI_position_.at(ind) = 229 - + // output_combined_position_and_velocity_array.at(ind); 230 - // list_of_LVLH_forces_at_this_time_ = list_of_LVLH_forces_at_one_timestep_past; + // ECI_velocity_.at(ind) = 231 - // list_of_ECI_forces_at_this_time_ = list_of_ECI_forces_at_one_timestep_past; + // output_combined_position_and_velocity_array.at(ind + 3); 232 - + // // also update the perifocal versions 233 - // // Update orbital parameters + // perifocal_position_ = convert_ECI_to_perifocal(ECI_position_); 234 - // update_orbital_elements_from_position_and_velocity(); + // perifocal_velocity_ = convert_ECI_to_perifocal(ECI_velocity_); 235 - + // } 236 - // return; + // t_ += input_step_size; 237 - // } + 238 - + // list_of_LVLH_forces_at_this_time_ = 239 - // Objective: add a LVLH frame thrust profile to the satellite + // list_of_LVLH_forces_at_one_timestep_past; list_of_ECI_forces_at_this_time_ 240 + + // = list_of_ECI_forces_at_one_timestep_past; + + + 241 + + + + + + + 242 + + + + // // Update orbital parameters + + + 243 + + + + // update_orbital_elements_from_position_and_velocity(); + + + 244 + + + + + + + 245 + + + + // return; + + + 246 + + + + // } + + + 247 + + + + + + + 248 + + + + // Objective: add a LVLH frame thrust profile to the satellite + + + 249 + + 10 void Satellite::add_LVLH_thrust_profile( - 241 + 250 const std::array<double, 3> input_LVLH_thrust_vector, - 242 + 251 const double input_thrust_start_time, const double input_thrust_end_time) { - 243 + 252 10 ThrustProfileLVLH new_thrust_profile( - 244 + 253 10 input_thrust_start_time, input_thrust_end_time, input_LVLH_thrust_vector); - 245 + 254 10 thrust_profile_list_.push_back(new_thrust_profile); - 246 + 255
2/2 @@ -1833,861 +1898,882 @@

GCC Code Coverage Report

if (input_thrust_start_time == t_) { - 247 + 256 2 list_of_LVLH_forces_at_this_time_.push_back(input_LVLH_thrust_vector); - 248 + 257 2 std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( - 249 + 258 2 input_LVLH_thrust_vector, ECI_position_, ECI_velocity_); - 250 + 259 2 list_of_ECI_forces_at_this_time_.push_back(ECI_thrust_vector); - 251 + 260 2 } - 252 + 261 10 } - 253 + 262 - 254 + 263 // Alternate input argument style - 255 + 264 - 12 + 3495723 void Satellite::add_LVLH_thrust_profile( - 256 + 265 const std::array<double, 3> input_LVLH_normalized_thrust_direction, - 257 + 266 const double input_LVLH_thrust_magnitude, - 258 + 267 const double input_thrust_start_time, const double input_thrust_end_time) { - 259 + 268 - 12 + 3495723 ThrustProfileLVLH new_thrust_profile( - 260 + 269 - 12 + 3495723 input_thrust_start_time, input_thrust_end_time, - 261 + 270 - 12 + 3495723 input_LVLH_normalized_thrust_direction, input_LVLH_thrust_magnitude); - 262 + 271 - 12 + 3495723 thrust_profile_list_.push_back(new_thrust_profile); - 263 + 272 - 264 + 273 - 12 + 3495723 std::array<double, 3> LVLH_thrust_vec = {0, 0, 0}; - 265 + 274 - 266 + 275
2/2
-
✓ Branch 0 taken 12 times.
-
✓ Branch 1 taken 36 times.
+
✓ Branch 0 taken 3495723 times.
+
✓ Branch 1 taken 10487169 times.
- 48 + 13982892 for (size_t ind = 0; ind < 3; ind++) { - 267 + 276 - 72 + 20974338 LVLH_thrust_vec.at(ind) = input_LVLH_thrust_magnitude * - 268 + 277 - 36 + 10487169 input_LVLH_normalized_thrust_direction.at(ind); - 269 + 278 - 36 + 10487169 } - 270 + 279 - 271 + 280
2/2
✓ Branch 0 taken 4 times.
-
✓ Branch 1 taken 8 times.
+
✓ Branch 1 taken 3495719 times.
- 12 + 3495723 if (input_thrust_start_time == t_) { - 272 + 281 - 8 + 3495719 list_of_LVLH_forces_at_this_time_.push_back(LVLH_thrust_vec); - 273 + 282 - 8 + 3495719 std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( - 274 + 283 - 8 + 3495719 LVLH_thrust_vec, ECI_position_, ECI_velocity_); - 275 + 284 - 8 + 3495719 list_of_ECI_forces_at_this_time_.push_back(ECI_thrust_vector); - 276 + 285 - 8 + 3495719 } - 277 + 286 - 12 + 3495723 } - 278 + 287 - 279 + 288 - // Now the version for argument of periapsis change maneuvers + // Now the version for argument of periapsis change maneuvers - 280 + 289 ✗ - void Satellite::add_LVLH_thrust_profile(const double input_thrust_start_time, const double final_arg_of_periapsis, + void Satellite::add_LVLH_thrust_profile(const double input_thrust_start_time, - 281 + 290 - const double input_thrust_magnitude) { + const double final_arg_of_periapsis, - 282 + 291 + + + + const double input_thrust_magnitude) { + + + 292 ✗ - ThrustProfileLVLH thrust_profile(input_thrust_start_time,final_arg_of_periapsis,input_thrust_magnitude, + ThrustProfileLVLH thrust_profile( - 283 + 293 ✗ - arg_of_periapsis_, eccentricity_, a_, m_); + input_thrust_start_time, final_arg_of_periapsis, input_thrust_magnitude, - 284 + 294 ✗ - thrust_profile_list_.push_back(thrust_profile); + arg_of_periapsis_, eccentricity_, a_, m_); - 285 + 295 ✗ - } + thrust_profile_list_.push_back(thrust_profile); - 286 + 296 + + + ✗ + } + + + 297 - 287 + 298 - 8948011 + 12466920 int Satellite::update_orbital_elements_from_position_and_velocity() { - 288 + 299 // Anytime the orbit is changed via external forces, need to update the - 289 + 300 // orbital parameters of the satellite. True anomaly should change over time - 290 + 301 // even in absence of external forces Using approach from Fundamentals of - 291 + 302 // Astrodynamics - 292 + 303 - 8948011 + 12466920 int error_code = 0; // 0 represents nominal operation - 293 + 304 - 8948011 - double mu_Earth = G*mass_Earth; + 12466920 + double mu_Earth = G * mass_Earth; - 294 + 305 - 17896022 + 24933840 Vector3d position_vector = {ECI_position_.at(0), ECI_position_.at(1), - 295 + 306 - 8948011 + 12466920 ECI_position_.at(2)}; - 296 + 307 - 17896022 + 24933840 Vector3d velocity_vector = {ECI_velocity_.at(0), ECI_velocity_.at(1), - 297 + 308 - 8948011 + 12466920 ECI_velocity_.at(2)}; - 298 + 309 - 8948011 + 12466920 Vector3d h_vector = position_vector.cross(velocity_vector); - 299 + 310 - 8948011 + 12466920 double h = h_vector.norm(); - 300 + 311 - 301 + 312 - 8948011 + 12466920 Vector3d n_vector = {-h_vector(1), h_vector(0), 0}; - 302 + 313 - 8948011 + 12466920 double n = n_vector.norm(); - 303 + 314 - 304 + 315 - 8948011 + 12466920 double v_magnitude = get_speed(); - 305 + 316 - 8948011 + 12466920 double r_magnitude = get_radius(); - 306 + 317 - 307 + 318 Vector3d e_vec_component_1 = - 308 + 319 - 8948011 - (1.0 / mu_Earth) * (v_magnitude * v_magnitude - (mu_Earth / r_magnitude)) * + 37400760 + (1.0 / mu_Earth) * - 309 + 320 - - position_vector; + 24933840 + (v_magnitude * v_magnitude - (mu_Earth / r_magnitude)) * position_vector; - 310 + 321 - - Vector3d e_vec_component_2 = + 37400760 + Vector3d e_vec_component_2 = (1.0 / mu_Earth) * - 311 + 322 - 8948011 - (1.0 / mu_Earth) * (position_vector.dot(velocity_vector)) * velocity_vector; + 24933840 + (position_vector.dot(velocity_vector)) * - 312 + 323 - 8948011 + + velocity_vector; + + + 324 + + + 12466920 Vector3d e_vec = e_vec_component_1 - e_vec_component_2; - 313 + 325 - 8948011 + 12466920 double calculated_eccentricity = e_vec.norm(); - 314 + 326 - 315 + 327 - 8948011 + 12466920 double calculated_p = h * h / mu_Earth; - 316 + 328 - 317 + 329 - 8948011 + 12466920 double calculated_i = acos(h_vector(2) / h); - 318 + 330 - 319 + 331 - 8948011 + 12466920 double calculated_RAAN = acos(n_vector(0) / n); - 320 + 332
2/2
-
✓ Branch 0 taken 5127416 times.
+
✓ Branch 0 taken 8646325 times.
✓ Branch 1 taken 3820595 times.
- 8948011 + 12466920 if (n_vector(1) < 0) { - 321 + 333 3820595 calculated_RAAN = 2 * M_PI - calculated_RAAN; - 322 + 334 3820595 } - 323 + 335 - 324 + 336 // Need to treat the e \approx 0 case (circular orbits) specially - 325 + 337 double calculated_arg_of_periapsis; - 326 + 338 double calculated_true_anomaly; - 327 + 339
2/2
-
✓ Branch 0 taken 8948007 times.
+
✓ Branch 0 taken 12466916 times.
✓ Branch 1 taken 4 times.
- 8948011 + 12466920 if (calculated_eccentricity > pow(10, -15)) { - 328 + 340 - 8948007 + 12466916 calculated_arg_of_periapsis = - 329 + 341 - 8948007 + 12466916 acos(n_vector.dot(e_vec) / (n * calculated_eccentricity)); - 330 + 342
2/2
-
✓ Branch 0 taken 8947859 times.
+
✓ Branch 0 taken 12466768 times.
✓ Branch 1 taken 148 times.
- 8948007 + 12466916 if (e_vec(2) < 0) { - 331 + 343 148 calculated_arg_of_periapsis = 2 * M_PI - calculated_arg_of_periapsis; - 332 + 344 148 } - 333 + 345 - 17896014 + 24933832 calculated_true_anomaly = acos(e_vec.dot(position_vector) / - 334 + 346 - 8948007 - (calculated_eccentricity * r_magnitude)); + 12466916 + (calculated_eccentricity * r_magnitude)); - 335 + 347
1/2
-
✓ Branch 0 taken 8948007 times.
+
✓ Branch 0 taken 12466916 times.
✗ Branch 1 not taken.
- 8948007 + 12466916 if (std::isnan(calculated_true_anomaly)) { - 336 + 348 // First try arg of the following acos call to a float to avoid bug - 337 + 349 - // where it ended up being represented by a value with magnitude + // where it ended up being represented by a value with magnitude - 338 + 350 // slightly larger than one, causing NaN in output of acos - 339 + 351 ✗ - float true_anomaly_acos_arg_float = e_vec.dot(position_vector) / + float true_anomaly_acos_arg_float = - 340 + 352 ✗ - (calculated_eccentricity * r_magnitude); + e_vec.dot(position_vector) / (calculated_eccentricity * r_magnitude); - 341 + 353 calculated_true_anomaly = acos(true_anomaly_acos_arg_float); - 342 + 354 if (std::isnan(calculated_true_anomaly)) { - 343 + 355 std::cout << "NaN true anomaly encountered.\n"; - 344 + 356 error_code = 10; - 345 + 357 } - 346 + 358 } - 347 + 359
2/2
-
✓ Branch 0 taken 4988149 times.
-
✓ Branch 1 taken 3959858 times.
+
✓ Branch 0 taken 6744257 times.
+
✓ Branch 1 taken 5722659 times.
- 8948007 + 12466916 if (position_vector.dot(velocity_vector) < 0) { - 348 + 360 - 3959858 + 5722659 calculated_true_anomaly = 2 * M_PI - calculated_true_anomaly; - 349 + 361 - 3959858 + 5722659 } - 350 + 362 - 351 + 363 - 8948007 + 12466916 } else { - 352 + 364 // Approximately circular orbits - 353 + 365 // For this case, I'll set the true anomaly to be the argument of latitude - 354 + 366 // (which is valid when arg of periapsis is 0, which is what I'm setting it - 355 + 367 // to) Refs: https://en.wikipedia.org/wiki/True_anomaly#Circular_orbit , - 356 + 368 // https://en.wikipedia.org/wiki/Argument_of_latitude , - 357 + 369 // https://en.wikipedia.org/wiki/Argument_of_periapsis - 358 + 370 4 calculated_arg_of_periapsis = 0; // Setting this - 359 + 371 - 360 + 372 4 double calculated_arg_of_latitude = - 361 + 373 4 acos(n_vector.dot(position_vector) / (n * r_magnitude)); - 362 + 374
1/2 @@ -2701,1427 +2787,1483 @@

GCC Code Coverage Report

if (position_vector(2) < 0) { - 363 + 375 4 calculated_arg_of_latitude = (2 * M_PI - calculated_arg_of_latitude); - 364 + 376 4 } - 365 + 377 4 calculated_true_anomaly = calculated_arg_of_latitude; // For this case - 366 + 378 } - 367 + 379 - 368 + 380 - 8948011 + 12466920 double calculated_a = - 369 + 381 - 8948011 + 12466920 calculated_p / (1.0 - calculated_eccentricity * calculated_eccentricity); - 370 + 382 - 371 + 383 // Update stored values of these orbital elements - 372 + 384 - 373 + 385 - 8948011 + 12466920 a_ = calculated_a; - 374 + 386 - 8948011 + 12466920 eccentricity_ = calculated_eccentricity; - 375 + 387 - 8948011 + 12466920 inclination_ = calculated_i; - 376 + 388 - 8948011 + 12466920 raan_ = calculated_RAAN; - 377 + 389 - 8948011 + 12466920 arg_of_periapsis_ = calculated_arg_of_periapsis; - 378 + 390 - 8948011 + 12466920 true_anomaly_ = calculated_true_anomaly; - 379 + 391 - 380 + 392 - 8948011 + 12466920 return error_code; - 381 + 393 } - 382 + 394 - 383 + 395 9 std::array<double, 6> Satellite::get_orbital_elements() { - 384 + 396 std::array<double, 6> orbit_elems_array; - 385 + 397 9 orbit_elems_array.at(0) = a_; - 386 + 398 9 orbit_elems_array.at(1) = eccentricity_; - 387 + 399 9 orbit_elems_array.at(2) = inclination_; - 388 + 400 9 orbit_elems_array.at(3) = raan_; - 389 + 401 9 orbit_elems_array.at(4) = arg_of_periapsis_; - 390 + 402 9 orbit_elems_array.at(5) = true_anomaly_; - 391 + 403 9 return orbit_elems_array; - 392 + 404 } - 393 + 405 - 394 + 406 - 8948009 + 12466918 std::pair<double, int> Satellite::evolve_RK45( - 395 + 407 const double input_epsilon, const double input_step_size, - 396 + 408 const bool perturbation, const bool atmospheric_drag, - 397 + 409 const std::pair<double, double> drag_elements) { - 398 + 410 + + + + // std::cout << "In EvolveRK45, received perturbation bool: " << perturbation + + + 411 + + + + // << "\n"; + + + 412 // perturbation is a flag which, when set to true, currently accounts for J2 - 399 + 413 // perturbation. - 400 + 414 - 401 + 415 // Let's do a single RK45_step call with y_n combined between orbital motion - 402 + 416 // and attitude variables, - 403 + 417 // y_n = {ECI_position_x, ECI_position_y, ECI_position_z, ECI_velocity_x, - 404 + 418 // ECI_velocity_y, ECI_velocity_z, q_0, q_1, q_2, q_3, omega_x, omega_y, - 405 + 419 // omega_z} Where the quaternion represents the attitude of the spacecraft - 406 + 420 // body frame with respect to the LVLH frame, and omega_i is the angular - 407 + 421 // velocity around the ith axis of the body frame with respect to the LVLH - 408 + 422 // frame, represented in the body frame - 409 + 423 - 410 + 424 // The tuple drag_elements contains the F_10 value and the A_p value used for - 411 + 425 // atmospheric drag calculations, if applicable - 412 + 426 // F_10 is the first element, A_p is the second element - 413 + 427 - 8948009 + 12466918 double input_F_10 = drag_elements.first; - 414 + 428 - 8948009 + 12466918 double input_A_p = drag_elements.second; - 415 + 429 - 416 + 430 - // Add any thrusts from an argument of periapsis change maneuver, if applicable + // Initialize arg of periapsis change thrust profile from current orbital - 417 + 431 + + + + // parameters, if there is one that hasn't already been initialized + + + 432 + + + 12466918 + check_for_maneuvers_to_initialize(); + + + 433 + + + + // Add any thrusts from an argument of periapsis change maneuver, if + + + 434 + + + + // applicable + + + 435 - 8948009 + 12466918 int arg_of_periapsis_code = add_arg_of_periapsis_change_thrust(); - 418 + 436 - 419 + 437 std::array<double, 13> - 420 + 438 - 8948009 + 12466918 combined_initial_position_velocity_quaternion_angular_velocity_array = {}; - 421 + 439 std::pair<std::array<double, 3>, std::array<double, 3>> - 422 + 440 - 8948009 + 12466918 output_position_velocity_pair = {}; - 423 + 441 - 424 + 442
2/2
-
✓ Branch 0 taken 26844027 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 37400754 times.
+
✓ Branch 1 taken 12466918 times.
- 35792036 + 49867672 for (size_t ind = 0; ind < 3; ind++) { - 425 + 443 - 26844027 + 37400754 combined_initial_position_velocity_quaternion_angular_velocity_array.at( - 426 + 444 - 53688054 + 74801508 ind) = ECI_position_.at(ind); - 427 + 445 - 26844027 + 37400754 } - 428 + 446
2/2
-
✓ Branch 0 taken 26844027 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 37400754 times.
+
✓ Branch 1 taken 12466918 times.
- 35792036 + 49867672 for (size_t ind = 3; ind < 6; ind++) { - 429 + 447 - 26844027 + 37400754 combined_initial_position_velocity_quaternion_angular_velocity_array.at( - 430 + 448 - 53688054 + 74801508 ind) = ECI_velocity_.at(ind - 3); - 431 + 449 - 26844027 + 37400754 } - 432 + 450
2/2
-
✓ Branch 0 taken 35792036 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 49867672 times.
+
✓ Branch 1 taken 12466918 times.
- 44740045 + 62334590 for (size_t ind = 6; ind < 10; ind++) { - 433 + 451 - 35792036 + 49867672 combined_initial_position_velocity_quaternion_angular_velocity_array.at( - 434 + 452 - 71584072 + 99735344 ind) = quaternion_satellite_bodyframe_wrt_LVLH_.at(ind - 6); - 435 + 453 - 35792036 + 49867672 } - 436 + 454 - 437 + 455
2/2
-
✓ Branch 0 taken 26844027 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 37400754 times.
+
✓ Branch 1 taken 12466918 times.
- 35792036 + 49867672 for (size_t ind = 10; ind < 13; ind++) { - 438 + 456 - 26844027 + 37400754 combined_initial_position_velocity_quaternion_angular_velocity_array.at( - 439 + 457 - 53688054 + 74801508 ind) = body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(ind - 10); - 440 + 458 - 26844027 + 37400754 } - 441 + 459 - 442 + 460 Matrix3d LVLH_to_body_transformation_matrix = - 443 + 461 - 8948009 + 12466918 LVLH_to_body_transformation_matrix_from_quaternion( - 444 + 462 - 8948009 + 12466918 quaternion_satellite_bodyframe_wrt_LVLH_); - 445 + 463 - 446 + 464 - 8948009 + 12466918 Vector3d body_angular_velocity_vec_wrt_LVLH_in_body_frame_eigenform = { - 447 + 465 - 8948009 + 12466918 body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(0), - 448 + 466 - 8948009 + 12466918 body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(1), - 449 + 467 - 8948009 + 12466918 body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(2)}; - 450 + 468 - 451 + 469 - 8948009 + 12466918 Vector3d omega_I = calculate_omega_I( - 452 + 470 - 8948009 + 12466918 body_angular_velocity_vec_wrt_LVLH_in_body_frame_eigenform, - 453 + 471 - 8948009 + 12466918 LVLH_to_body_transformation_matrix, orbital_rate_); - 454 + 472 - 455 + 473 - 8948009 + 12466918 Vector3d omega_LVLH_wrt_inertial_in_LVLH = {0, -orbital_rate_, 0}; - 456 + 474 - 457 + 475 - 8948009 + 12466918 Matrix3d J_matrix = construct_J_matrix(J_11_, J_22_, J_33_); - 458 + 476 - 459 + 477 std::pair<std::array<double, 13>, std::pair<double, double>> output_pair = - 460 + 478
1/2
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
- 8948009 + 12466918 RK45_step<13>( - 461 + 479 - 8948009 + 12466918 combined_initial_position_velocity_quaternion_angular_velocity_array, - 462 + 480 - 8948009 + 12466918 input_step_size, - 463 + 481 - 8948009 + 12466918 RK45_combined_orbit_position_velocity_attitude_deriv_function, - 464 + 482
3/6
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 8948009 times.
+
✓ Branch 2 taken 12466918 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 8948009 times.
+
✓ Branch 4 taken 12466918 times.
✗ Branch 5 not taken.
- 8948009 + 12466918 J_matrix, bodyframe_torque_profile_list_, omega_I, - 465 + 483
1/2
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
- 8948009 + 12466918 orbital_angular_acceleration_, LVLH_to_body_transformation_matrix, - 466 + 484
2/4
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 8948009 times.
+
✓ Branch 2 taken 12466918 times.
✗ Branch 3 not taken.
- 8948009 + 12466918 omega_LVLH_wrt_inertial_in_LVLH, m_, thrust_profile_list_, - 467 + 485 - 8948009 + 12466918 inclination_, arg_of_periapsis_, true_anomaly_, input_F_10, input_A_p, - 468 + 486 - 8948009 + 12466918 A_s_, perturbation, atmospheric_drag, t_, input_epsilon); - 469 + 487 - 470 + 488 std::array<double, 13> - 471 + 489 output_combined_position_velocity_quaternion_angular_velocity_array = - 472 + 490 - 8948009 + 12466918 output_pair.first; - 473 + 491 - 8948009 + 12466918 double step_size_successfully_used_here = output_pair.second.first; - 474 + 492 - 8948009 + 12466918 double new_step_size = output_pair.second.second; - 475 + 493 - 476 + 494
2/2
-
✓ Branch 0 taken 26844027 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 37400754 times.
+
✓ Branch 1 taken 12466918 times.
- 35792036 + 49867672 for (size_t ind = 0; ind < 3; ind++) { - 477 + 495 - 26844027 + 37400754 ECI_position_.at(ind) = - 478 + 496 - 26844027 + 37400754 output_combined_position_velocity_quaternion_angular_velocity_array.at( - 479 + 497 - 26844027 + 37400754 ind); - 480 + 498 - 26844027 + 37400754 ECI_velocity_.at(ind) = - 481 + 499 - 26844027 + 37400754 output_combined_position_velocity_quaternion_angular_velocity_array.at( - 482 + 500 - 26844027 + 37400754 ind + 3); - 483 + 501 // Also update the perifocal versions - 484 + 502 - 26844027 + 37400754 perifocal_position_ = convert_ECI_to_perifocal(ECI_position_); - 485 + 503 - 26844027 + 37400754 perifocal_velocity_ = convert_ECI_to_perifocal(ECI_velocity_); - 486 + 504 - 26844027 + 37400754 } - 487 + 505 - 8948009 + 12466918 t_ += step_size_successfully_used_here; - 488 + 506 - 489 + 507
2/2
-
✓ Branch 0 taken 35792036 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 49867672 times.
+
✓ Branch 1 taken 12466918 times.
- 44740045 + 62334590 for (size_t ind = 0; ind < quaternion_satellite_bodyframe_wrt_LVLH_.size(); - 490 + 508 - 35792036 + 49867672 ind++) { - 491 + 509 - 35792036 + 49867672 quaternion_satellite_bodyframe_wrt_LVLH_.at(ind) = - 492 + 510 - 35792036 + 49867672 output_combined_position_velocity_quaternion_angular_velocity_array.at( - 493 + 511 - 35792036 + 49867672 ind + 6); - 494 + 512 - 35792036 + 49867672 } - 495 + 513 - 8948009 + 12466918 quaternion_satellite_bodyframe_wrt_LVLH_ = - 496 + 514 - 8948009 + 12466918 normalize_quaternion(quaternion_satellite_bodyframe_wrt_LVLH_); - 497 + 515 std::array<double, 3> updated_roll_yaw_pitch = - 498 + 516 - 8948009 + 12466918 convert_quaternion_to_roll_yaw_pitch_angles( - 499 + 517 - 8948009 + 12466918 quaternion_satellite_bodyframe_wrt_LVLH_); - 500 + 518 - 501 + 519 - 8948009 + 12466918 roll_angle_ = updated_roll_yaw_pitch.at(0); - 502 + 520 - 8948009 + 12466918 yaw_angle_ = updated_roll_yaw_pitch.at(1); - 503 + 521 - 8948009 + 12466918 pitch_angle_ = updated_roll_yaw_pitch.at(2); - 504 + 522 - 505 + 523
2/2
-
✓ Branch 0 taken 26844027 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 37400754 times.
+
✓ Branch 1 taken 12466918 times.
- 35792036 + 49867672 for (size_t ind = 0; - 506 + 524 - 35792036 + 49867672 ind < body_angular_velocity_vec_wrt_LVLH_in_body_frame_.size(); ind++) { - 507 + 525 - 26844027 + 37400754 body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(ind) = - 508 + 526 - 26844027 + 37400754 output_combined_position_velocity_quaternion_angular_velocity_array.at( - 509 + 527 - 26844027 + 37400754 ind + 10); - 510 + 528 - 26844027 + 37400754 } - 511 + 529 - 512 + 530 // Update orbital parameters - 513 + 531 - 8948009 + 12466918 int orbit_elems_error_code = - 514 + 532 - 8948009 + 12466918 update_orbital_elements_from_position_and_velocity(); - 515 + 533 - 8948009 + 12466918 orbital_rate_ = calculate_instantaneous_orbit_rate(); - 516 + 534 - 8948009 + 12466918 orbital_angular_acceleration_ = - 517 + 535 - 8948009 + 12466918 calculate_instantaneous_orbit_angular_acceleration(); - 518 + 536 - 8948009 + 12466918 std::pair<double, int> evolve_RK45_output_pair; - 519 + 537 // Orbital radius shouldn't be less than or equal to Earth's radius - 520 + 538 - 8948009 + 12466918 double new_orbital_radius = get_radius(); - 521 + 539
1/2
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
- 8948009 - if (new_orbital_radius <= radius_Earth){ + 12466918 + if (new_orbital_radius <= radius_Earth) { - 522 + 540 orbit_elems_error_code = 2; - 523 + 541 } - 524 + 542 - 8948009 + 12466918 evolve_RK45_output_pair.first = new_step_size; - 525 + 543 - 8948009 + 12466918 evolve_RK45_output_pair.second = orbit_elems_error_code; - 526 + 544 - 527 + 545 - // If you just added a temporally localized thrust profile stemming from an argument of periapsis change thrust profile, + // If you just added a temporally localized thrust profile stemming from an - 528 + 546 - // remove it now that it's no longer needed to avoid bloat of the thrust profile list + // argument of periapsis change thrust profile, remove it now that it's no - 529 + 547 + + + + // longer needed to avoid bloat of the thrust profile list + + + 548
- 1/2 + 2/2
-
✓ Branch 0 taken 8948009 times.
-
✗ Branch 1 not taken.
+
✓ Branch 0 taken 8971207 times.
+
✓ Branch 1 taken 3495711 times.
- 8948009 - if (arg_of_periapsis_code == 1) { + 12466918 + if (arg_of_periapsis_code == 1) { - 530 + 549 - ✗ - thrust_profile_list_.pop_back(); + 3495711 + thrust_profile_list_.pop_back(); - 531 + 550 - ✗ - } + 3495711 + } - 532 + 551 - 8948009 + 12466918 return evolve_RK45_output_pair; - 533 + 552} - 534 + 553 - 535 + 554 // Returns a specific orbital element - 536 + 555 - 95664 - double Satellite::get_orbital_parameter(const std::string orbital_parameter_name) { + 95672 + double Satellite::get_orbital_parameter( - 537 + 556 + + + + const std::string orbital_parameter_name) { + + + 557
2/2
-
✓ Branch 0 taken 9350 times.
-
✓ Branch 1 taken 86314 times.
+
✓ Branch 0 taken 9352 times.
+
✓ Branch 1 taken 86320 times.
- 95664 + 95672 if (orbital_parameter_name == "Semimajor Axis") { - 538 + 558 - 9350 + 9352 return a_; - 539 + 559
2/2
-
✓ Branch 0 taken 9346 times.
-
✓ Branch 1 taken 76968 times.
+
✓ Branch 0 taken 9348 times.
+
✓ Branch 1 taken 76972 times.
- 86314 + 86320 } else if (orbital_parameter_name == "Eccentricity") { - 540 + 560 - 9346 + 9348 return eccentricity_; - 541 + 561
2/2
✓ Branch 0 taken 9344 times.
-
✓ Branch 1 taken 67624 times.
+
✓ Branch 1 taken 67628 times.
- 76968 + 76972 } else if (orbital_parameter_name == "Inclination") { - 542 + 562 9344 - return inclination_*(180/M_PI); // Returns val in degrees + return inclination_ * (180 / M_PI); // Returns val in degrees - 543 + 563
2/2
✓ Branch 0 taken 9344 times.
-
✓ Branch 1 taken 58280 times.
+
✓ Branch 1 taken 58284 times.
- 67624 + 67628 } else if (orbital_parameter_name == "RAAN") { - 544 + 564 9344 - return raan_ * (180.0 / M_PI); // Returns val in degrees + return raan_ * (180.0 / M_PI); // Returns val in degrees - 545 + 565
2/2
-
✓ Branch 0 taken 9344 times.
+
✓ Branch 0 taken 9348 times.
✓ Branch 1 taken 48936 times.
- 58280 + 58284 } else if (orbital_parameter_name == "Argument of Periapsis") { - 546 + 566 - 9344 - return arg_of_periapsis_ * (180.0 / M_PI); // Returns val in degrees + 9348 + return arg_of_periapsis_ * (180.0 / M_PI); // Returns val in degrees - 547 + 567
2/2 @@ -4135,14 +4277,14 @@

GCC Code Coverage Report

} else if (orbital_parameter_name == "True Anomaly") { - 548 + 568 20903 - return true_anomaly_ * (180.0 / M_PI); // Returns val in degrees + return true_anomaly_ * (180.0 / M_PI); // Returns val in degrees - 549 + 569
2/2 @@ -4156,14 +4298,14 @@

GCC Code Coverage Report

} else if (orbital_parameter_name == "Orbital Rate") { - 550 + 570 9344 return orbital_rate_; - 551 + 571
2/2 @@ -4177,14 +4319,14 @@

GCC Code Coverage Report

} else if (orbital_parameter_name == "Orbital Angular Acceleration") { - 552 + 572 9344 return orbital_angular_acceleration_; - 553 + 573
2/2 @@ -4198,21 +4340,21 @@

GCC Code Coverage Report

} else if (orbital_parameter_name == "Total Energy") { - 554 + 574 9344 return get_total_energy(); - 555 + 575 } else { - 556 + 576
1/2 @@ -4226,84 +4368,84 @@

GCC Code Coverage Report

throw std::invalid_argument("Value name not recognized"); - 557 + 577 } - 558 + 578 - 95663 + 95671 } - 559 + 579 - 560 + 580 // Objective: add a body frame torque profile to the satellite - 561 + 581 10 void Satellite::add_bodyframe_torque_profile( - 562 + 582 const std::array<double, 3> input_bodyframe_torque_vector, - 563 + 583 const double input_torque_start_time, const double input_torque_end_time) { - 564 + 584 20 BodyframeTorqueProfile new_torque_profile(input_torque_start_time, - 565 + 585 10 input_torque_end_time, - 566 + 586 10 input_bodyframe_torque_vector); - 567 + 587 10 bodyframe_torque_profile_list_.push_back(new_torque_profile); - 568 + 588
2/2 @@ -4317,84 +4459,84 @@

GCC Code Coverage Report

if (input_torque_start_time == 0) { - 569 + 589 1 list_of_body_frame_torques_at_this_time_.push_back( - 570 + 590 input_bodyframe_torque_vector); - 571 + 591 1 } - 572 + 592 10 } - 573 + 593 // Alternate input argument style - 574 + 594 10 void Satellite::add_bodyframe_torque_profile( - 575 + 595 const std::array<double, 3> input_bodyframe_direction_unit_vec, - 576 + 596 const double input_bodyframe_torque_magnitude, - 577 + 597 const double input_torque_start_time, const double input_torque_end_time) { - 578 + 598 10 std::array<double, 3> input_bodyframe_torque_vector = {0, 0, 0}; - 579 + 599 - 580 + 600
2/2 @@ -4408,63 +4550,63 @@

GCC Code Coverage Report

for (size_t ind = 0; ind < 3; ind++) { - 581 + 601 30 input_bodyframe_torque_vector.at(ind) = - 582 + 602 60 input_bodyframe_torque_magnitude * - 583 + 603 30 input_bodyframe_direction_unit_vec.at(ind); - 584 + 604 30 } - 585 + 605 20 BodyframeTorqueProfile new_torque_profile(input_torque_start_time, - 586 + 606 10 input_torque_end_time, - 587 + 607 10 input_bodyframe_torque_vector); - 588 + 608 10 bodyframe_torque_profile_list_.push_back(new_torque_profile); - 589 + 609
1/2 @@ -4478,448 +4620,448 @@

GCC Code Coverage Report

if (input_torque_start_time == 0) { - 590 + 610 list_of_body_frame_torques_at_this_time_.push_back( - 591 + 611 input_bodyframe_torque_vector); - 592 + 612 } - 593 + 613 10 } - 594 + 614 - 595 + 615 - 8948064 + 12466975 double Satellite::calculate_instantaneous_orbit_rate() { - 596 + 616 // Need to figure out how to calculate the equivalent of w_0 in section 4.3.1 - 597 + 617 // of - 598 + 618 // https://ntrs.nasa.gov/api/citations/20240009554/downloads/Space%20Attitude%20Development%20Control.pdf - 599 + 619 // but for general elliptical orbits Is this proportional to the rate of - 600 + 620 // change of the true anomaly? Proof sketched out here: - 601 + 621 // https://space.stackexchange.com/questions/21615/how-to-calculate-the-complete-true-anomaly-motion-in-an-elliptical-orbit - 602 + 622 - 17896128 + 24933950 Vector3d position_vector = {perifocal_position_.at(0), - 603 + 623 - 8948064 + 12466975 perifocal_position_.at(1), - 604 + 624 - 8948064 + 12466975 perifocal_position_.at(2)}; - 605 + 625 - 17896128 + 24933950 Vector3d velocity_vector = {perifocal_velocity_.at(0), - 606 + 626 - 8948064 + 12466975 perifocal_velocity_.at(1), - 607 + 627 - 8948064 + 12466975 perifocal_velocity_.at(2)}; - 608 + 628 - 8948064 + 12466975 Vector3d h_vector = position_vector.cross(velocity_vector); - 609 + 629 - 8948064 + 12466975 double h = h_vector.norm(); - 610 + 630 - 8948064 + 12466975 double r = get_radius(); - 611 + 631 - 8948064 + 12466975 double orbit_rate = h / (r * r); - 612 + 632 - 8948064 + 12466975 return orbit_rate; - 613 + 633 } - 614 + 634 - 615 + 635 - 8948064 + 12466975 double Satellite::calculate_instantaneous_orbit_angular_acceleration() { - 616 + 636 // Need to figure out how to calculate the equivalent of w_0^dot to get the - 617 + 637 // w_lvlh^dot term in Ch.4 of - 618 + 638 // https://ntrs.nasa.gov/api/citations/20240009554/downloads/Space%20Attitude%20Development%20Control.pdf - 619 + 639 // but for general elliptical orbits Proof sketched out here: - 620 + 640 // https://space.stackexchange.com/questions/21615/how-to-calculate-the-complete-true-anomaly-motion-in-an-elliptical-orbit - 621 + 641 // This assumes angular momentum is constant - 622 + 642 - 17896128 + 24933950 Vector3d position_vector = {perifocal_position_.at(0), - 623 + 643 - 8948064 + 12466975 perifocal_position_.at(1), - 624 + 644 - 8948064 + 12466975 perifocal_position_.at(2)}; - 625 + 645 - 17896128 + 24933950 Vector3d velocity_vector = {perifocal_velocity_.at(0), - 626 + 646 - 8948064 + 12466975 perifocal_velocity_.at(1), - 627 + 647 - 8948064 + 12466975 perifocal_velocity_.at(2)}; - 628 + 648 - 8948064 + 12466975 Vector3d h_vector = position_vector.cross(velocity_vector); - 629 + 649 - 8948064 + 12466975 double h = h_vector.norm(); - 630 + 650 - 8948064 + 12466975 double r = get_radius(); - 631 + 651 - 8948064 + 12466975 Vector3d unit_position_vector = position_vector; - 632 + 652 - 8948064 + 12466975 unit_position_vector.normalize(); - 633 + 653 - 8948064 + 12466975 double orbit_angular_acceleration = - 634 + 654 - 8948064 + 12466975 -2 * h / (r * r * r) * velocity_vector.dot(unit_position_vector); - 635 + 655 - 636 + 656 // Neglecting term relating to derivative of h for now (would be an h^dot / - 637 + 657 // r^2 term added to the above term) - 638 + 658 - 8948064 + 12466975 return orbit_angular_acceleration; - 639 + 659 } - 640 + 660 - 641 + 661 - 57 + 59 void Satellite::initialize_and_normalize_body_quaternion( - 642 + 662 const double roll_angle, const double pitch_angle, const double yaw_angle) { - 643 + 663 std::array<double, 4> quaternion = - 644 + 664 - 57 + 59 rollyawpitch_angles_to_quaternion(roll_angle, pitch_angle, yaw_angle); - 645 + 665 std::array<double, 4> normalized_quaternion = - 646 + 666 - 57 + 59 normalize_quaternion(quaternion); - 647 + 667 - 57 + 59 quaternion_satellite_bodyframe_wrt_LVLH_ = normalized_quaternion; - 648 + 668 - 57 + 59 return; - 649 + 669 } - 650 + 670 - 651 + 671 // Return a specific attitude-related value - 652 + 672 96215 double Satellite::get_attitude_val(std::string input_attitude_val_name) { - 653 + 673
2/2 @@ -4933,14 +5075,14 @@

GCC Code Coverage Report

if (input_attitude_val_name == "Roll") { - 654 + 674 9621 - return roll_angle_ * (180.0 / M_PI); // Returns val in degrees + return roll_angle_ * (180.0 / M_PI); // Returns val in degrees - 655 + 675
2/2 @@ -4954,14 +5096,14 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "Pitch") { - 656 + 676 9625 - return pitch_angle_ * (180.0 / M_PI); // Returns val in degrees + return pitch_angle_ * (180.0 / M_PI); // Returns val in degrees - 657 + 677
2/2 @@ -4975,14 +5117,14 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "Yaw") { - 658 + 678 9621 - return yaw_angle_ * (180.0 / M_PI); // Returns val in degrees + return yaw_angle_ * (180.0 / M_PI); // Returns val in degrees - 659 + 679
2/2 @@ -4996,14 +5138,21 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "omega_x") { - 660 + 680 9621 - return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(0) * (180.0 / M_PI); // Returns val in degrees/s + return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(0) * - 661 + 681 + + + + (180.0 / M_PI); // Returns val in degrees/s + + + 682
2/2 @@ -5017,14 +5166,21 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "omega_y") { - 662 + 683 9621 - return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(1) * (180.0 / M_PI); // Returns val in degrees/s + return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(1) * - 663 + 684 + + + + (180.0 / M_PI); // Returns val in degrees/s + + + 685
2/2 @@ -5038,14 +5194,21 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "omega_z") { - 664 + 686 9621 - return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(2) * (180.0 / M_PI); // Returns val in degrees/s + return body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(2) * - 665 + 687 + + + + (180.0 / M_PI); // Returns val in degrees/s + + + 688
2/2 @@ -5059,14 +5222,14 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "q_0") { - 666 + 689 9621 return quaternion_satellite_bodyframe_wrt_LVLH_.at(0); - 667 + 690
2/2 @@ -5080,14 +5243,14 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "q_1") { - 668 + 691 9621 return quaternion_satellite_bodyframe_wrt_LVLH_.at(1); - 669 + 692
2/2 @@ -5101,14 +5264,14 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "q_2") { - 670 + 693 9621 return quaternion_satellite_bodyframe_wrt_LVLH_.at(2); - 671 + 694
2/2 @@ -5122,21 +5285,21 @@

GCC Code Coverage Report

} else if (input_attitude_val_name == "q_3") { - 672 + 695 9621 return quaternion_satellite_bodyframe_wrt_LVLH_.at(3); - 673 + 696 } else { - 674 + 697
1/2 @@ -5150,221 +5313,587 @@

GCC Code Coverage Report

throw std::invalid_argument("Value name not recognized"); - 675 + 698 } - 676 + 699 96214 } - 677 + 700 - 678 + 701 - 55 + 57 void Satellite::initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame() { - 679 + 702 - 55 + 57 std::array<double, 3> initial_body_angular_velocity_in_LVLH_frame = { - 680 + 703 - 55 + 57 0, orbital_rate_, 0}; - 681 + 704 - 55 + 57 body_angular_velocity_vec_wrt_LVLH_in_body_frame_ = - 682 + 705 - 55 + 57 convert_array_from_LVLH_to_bodyframe( - 683 + 706 - 55 + 57 initial_body_angular_velocity_in_LVLH_frame, roll_angle_, yaw_angle_, - 684 + 707 - 55 + 57 pitch_angle_); // Because LVLH is always rotating around y axis to - 685 + 708 // keep z pointed towards Earth - 686 + 709 - 55 + 57 } - 687 + 710 - 8948009 + 12466918 int Satellite::add_arg_of_periapsis_change_thrust() { - 688 + 711 // Returning 0 means didn't find any arg of periapsis change thrust profiles - 689 + 712 - // Returning 1 means it did find one and added a temporally localized thrust at this time + // Returning 1 means it did find one and added a temporally localized thrust - 690 + 713 + + + + // at this time + + + 714
2/2
-
✓ Branch 0 taken 8948009 times.
-
✓ Branch 1 taken 7691628 times.
+
✓ Branch 0 taken 8971207 times.
+
✓ Branch 1 taken 11210535 times.
- 16639637 + 20181742 for (ThrustProfileLVLH thrust_profile : thrust_profile_list_) { - 691 + 715
- 1/6 + 4/4
-
✗ Branch 0 not taken.
+
✓ Branch 0 taken 3518907 times.
✓ Branch 1 taken 7691628 times.
-
✗ Branch 2 not taken.
-
✗ Branch 3 not taken.
-
✗ Branch 4 not taken.
-
✗ Branch 5 not taken.
+
✓ Branch 2 taken 23196 times.
+
✓ Branch 3 taken 3495711 times.
- 7691628 - if ((thrust_profile.arg_of_periapsis_change_thrust_profile) && (thrust_profile.t_start_ <= t_) && (thrust_profile.t_end_ >= t_)) { + 14729442 + if ((thrust_profile.arg_of_periapsis_change_thrust_profile) && - 692 + 716 +
+ 1/2 +
+
✓ Branch 0 taken 3518907 times.
+
✗ Branch 1 not taken.
+
+
- ✗ - std::array<double,3> thrust_direction_vec = {sin(true_anomaly_), 0, cos(true_anomaly_)}; + 3518907 + (thrust_profile.t_start_ <= t_) && (thrust_profile.t_end_ >= t_)) { - 693 + 717 + + + 6991422 + std::array<double, 3> thrust_direction_vec = {sin(true_anomaly_), 0, + + + 718 + + + 3495711 + cos(true_anomaly_)}; + + + 719 - 694 + 720 - ✗ - add_LVLH_thrust_profile(thrust_direction_vec, thrust_profile.sign_of_delta_omega*thrust_profile.thrust_magnitude_,t_,thrust_profile.t_end_); + 3495711 + add_LVLH_thrust_profile( - 695 + 721 + + + 3495711 + thrust_direction_vec, + + + 722 + + + 3495711 + thrust_profile.sign_of_delta_omega * thrust_profile.thrust_magnitude_, + + + 723 + + + 3495711 + t_, thrust_profile.t_end_); + + + 724 - // can add one with t_end stretching all the way to the t_end of the total arg of periapsis change maneuver because this temporary thrust profile will + // can add one with t_end stretching all the way to the t_end of the total - 696 + 725 - // be deleted after this RK45 step. This end time is given so that whatever timestep is chosen for this step, all intermediate calculated steps will + // arg of periapsis change maneuver because this temporary thrust profile - 697 + 726 - // also see this thrust. + // will be deleted after this RK45 step. This end time is given so that - 698 + 727 - ✗ - return 1; + + // whatever timestep is chosen for this step, all intermediate calculated - 699 + 728 + + + + // steps will also see this thrust. + + + 729 + + + 3495711 + return 1; + + + 730 } - 700 + 731 } - 701 + 732 - 8948009 + 8971207 return 0; - 702 + 733 - 8948009 + 12466918 } - 703 + 734 + + + 12466918 + void Satellite::check_for_maneuvers_to_initialize() { + + + 735 + +
+ 2/2 +
+
✓ Branch 0 taken 2 times.
+
✓ Branch 1 taken 12466918 times.
+
+
+ + 12466920 + for (size_t maneuver_index = 0; + + + 736 + + + 12466920 + maneuver_index < maneuvers_awaiting_initiation_.size(); + + + 737 + + + 2 + maneuver_index++) { + + + 738 + + + + std::pair<std::string, std::array<double, 3>> maneuver_info = + + + 739 + + + 2 + maneuvers_awaiting_initiation_.at(maneuver_index); + + + 740 + +
+ 1/2 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
+
+ + 2 + const double maneuver_start_time = maneuver_info.second.at(0); + + + 741 + +
+ 2/4 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
✓ Branch 2 taken 2 times.
+
✗ Branch 3 not taken.
+
+
+ + 2 + if ((maneuver_start_time <= t_) && + + + 742 + + + 2 + (maneuver_info.first == "Argument of Periapsis Change")) { + + + 743 + + + + // Need to initialize this maneuver + + + 744 + +
+ 1/2 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
+
+ + 2 + const double target_arg_of_periapsis_deg = maneuver_info.second.at(1); + + + 745 + + + 2 + const double target_arg_of_periapsis_rad = + + + 746 + + + 2 + target_arg_of_periapsis_deg * (M_PI / 180.0); + + + 747 + +
+ 1/2 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
+
+ + 2 + const double thrust_magnitude = maneuver_info.second.at(2); + + + 748 + +
+ 1/2 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
+
+ + 2 + ThrustProfileLVLH thrust_profile( + + + 749 + + + 2 + maneuver_start_time, target_arg_of_periapsis_rad, thrust_magnitude, + + + 750 + + + 2 + arg_of_periapsis_, eccentricity_, a_, m_); + + + 751 + +
+ 1/2 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
+
+ + 2 + thrust_profile_list_.push_back(thrust_profile); + + + 752 + +
+ 2/4 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
✓ Branch 2 taken 2 times.
+
✗ Branch 3 not taken.
+
+
+ + 4 + maneuvers_awaiting_initiation_.erase( + + + 753 + + + 2 + maneuvers_awaiting_initiation_.begin() + maneuver_index); + + + 754 + + + 2 + } + + + 755 + + + 2 + } + + + 756 + + + 12466918 + } + + + 757 + + + + + + + 758 + + + 2 + void Satellite::add_maneuver(const std::string maneuver_type, + + + 759 + + + + const double maneuver_start_time, + + + 760 + + + + const double final_parameter_val, + + + 761 + + + + const double thrust_magnitude) { + + + 762 + + + 6 + std::array<double, 3> maneuver_vals = {maneuver_start_time, + + + 763 + + + 4 + final_parameter_val, thrust_magnitude}; + + + 764 + + + 2 + std::pair<std::string, std::array<double, 3>> maneuver_info = {maneuver_type, + + + 765 + + + + maneuver_vals}; + + + 766 + +
+ 1/2 +
+
✓ Branch 0 taken 2 times.
+
✗ Branch 1 not taken.
+
+
+ + 2 + maneuvers_awaiting_initiation_.push_back(maneuver_info); + + + 767 + + + 2 + } + + + 768 diff --git a/tests/test_coverage_detailed.Satellite.h.016907876294210b00a2d880adf10425.html b/tests/test_coverage_detailed.Satellite.h.016907876294210b00a2d880adf10425.html index 73c0fb1..6bda5a5 100644 --- a/tests/test_coverage_detailed.Satellite.h.016907876294210b00a2d880adf10425.html +++ b/tests/test_coverage_detailed.Satellite.h.016907876294210b00a2d880adf10425.html @@ -26,7 +26,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -40,21 +40,21 @@

GCC Code Coverage Report

Lines: - 179 - 193 - 92.7% + 201 + 201 + 100.0% Functions: - 19 20 - 95.0% + 20 + 100.0% Branches: - 107 - 176 - 60.8% + 110 + 178 + 61.8% @@ -70,26 +70,26 @@

GCC Code Coverage Report

Call count Block coverage - BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>) (line 80)called 42 times100.0% - BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>, double) (line 86)called 2 times100.0% - BodyframeTorqueProfile::operator==(BodyframeTorqueProfile const&) (line 97)called 1 time100.0% - Satellite::Satellite(Satellite const&) (line 106)called 26974378 times100.0% - Satellite::Satellite(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 174)called 128 times100.0% - Satellite::get_ECI_position() (line 293)called 13489787 times100.0% - Satellite::get_instantaneous_time() (line 328)called 22422291 times100.0% - Satellite::get_mass() (line 327)called 2 times100.0% - Satellite::get_name() (line 329)called 2737 times100.0% - Satellite::get_radius() (line 306)called 35801632 times100.0% - Satellite::get_radius_ECI() (line 313)called 2 times100.0% - Satellite::get_speed() (line 295)called 8957373 times100.0% - Satellite::get_speed_ECI() (line 302)called 2 times100.0% - Satellite::get_total_energy() (line 317)called 9352 times100.0% - Satellite::operator=(Satellite const&) (line 106)called 2052 times100.0% - Satellite::~Satellite() (line 106)called 26974488 times100.0% - ThrustProfileLVLH::ThrustProfileLVLH(double, double, double, double, double, double, double) (line 47)not called0.0% - ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>) (line 30)called 22 times100.0% - ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>, double) (line 36)called 26 times100.0% - ThrustProfileLVLH::operator==(ThrustProfileLVLH const&) (line 67)called 1 time100.0% + BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>) (line 91)called 42 times100.0% + BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>, double) (line 97)called 2 times100.0% + BodyframeTorqueProfile::operator==(BodyframeTorqueProfile const&) (line 108)called 1 time100.0% + Satellite::Satellite(Satellite const&) (line 117)called 26974378 times100.0% + Satellite::Satellite(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 186)called 132 times100.0% + Satellite::get_ECI_position() (line 305)called 13489787 times100.0% + Satellite::get_instantaneous_time() (line 340)called 25941200 times100.0% + Satellite::get_mass() (line 339)called 4 times100.0% + Satellite::get_name() (line 341)called 2737 times100.0% + Satellite::get_radius() (line 318)called 49877272 times100.0% + Satellite::get_radius_ECI() (line 325)called 2 times100.0% + Satellite::get_speed() (line 307)called 12476282 times100.0% + Satellite::get_speed_ECI() (line 314)called 2 times100.0% + Satellite::get_total_energy() (line 329)called 9352 times100.0% + Satellite::operator=(Satellite const&) (line 117)called 2052 times100.0% + Satellite::~Satellite() (line 117)called 26974492 times100.0% + ThrustProfileLVLH::ThrustProfileLVLH(double, double, double, double, double, double, double) (line 48)called 4 times100.0% + ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>) (line 31)called 22 times100.0% + ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>, double) (line 37)called 6991448 times100.0% + ThrustProfileLVLH::operator==(ThrustProfileLVLH const&) (line 78)called 1 time100.0%
@@ -268,319 +268,403 @@

GCC Code Coverage Report

24 - 24 + 3495737 double t_start_ = {0}; 25 - 24 + 3495737 double t_end_ = {0}; 26 - 24 + 3495737 bool arg_of_periapsis_change_thrust_profile = false; 27 - 24 + 3495737 double sign_of_delta_omega = {1}; 28 - 24 - double thrust_magnitude_ = {0}; // Only used for argument of periapsis change thrust profiles + 3495737 + double thrust_magnitude_ = { 29 - 24 - std::array<double, 3> LVLH_force_vec_ = {0, 0, 0}; + + 0}; // Only used for argument of periapsis change thrust profiles 30 + 3495737 + std::array<double, 3> LVLH_force_vec_ = {0, 0, 0}; + + + 31 + + 22 ThrustProfileLVLH(const double t_start, const double t_end, - 31 + 32 11 const std::array<double, 3> LVLH_force_vec) { - 32 + 33 11 t_start_ = t_start; - 33 + 34 11 t_end_ = t_end; - 34 + 35 11 LVLH_force_vec_ = LVLH_force_vec; - 35 + 36 22 } - 36 + 37 - 26 + 6991448 ThrustProfileLVLH( - 37 + 38 const double t_start, const double t_end, - 38 + 39 const std::array<double, 3> LVLH_normalized_force_direction_vec, - 39 + 40 - 13 + 3495724 const double input_force_magnitude) { - 40 + 41 - 13 + 3495724 t_start_ = t_start; - 41 + 42 - 13 + 3495724 t_end_ = t_end; - 42 + 43
2/2
-
✓ Branch 0 taken 39 times.
-
✓ Branch 1 taken 13 times.
+
✓ Branch 0 taken 10487172 times.
+
✓ Branch 1 taken 3495724 times.
- 52 + 13982896 for (size_t ind = 0; ind < 3; ind++) { - - 43 - - - 39 - LVLH_force_vec_.at(ind) = - 44 - 39 - input_force_magnitude * LVLH_normalized_force_direction_vec.at(ind); + 10487172 + LVLH_force_vec_.at(ind) = 45 - 39 - } + 10487172 + input_force_magnitude * LVLH_normalized_force_direction_vec.at(ind); 46 - 26 - } + 10487172 + } 47 - ✗ - ThrustProfileLVLH(const double t_start, const double final_arg_of_periapsis, + 6991448 + } 48 - - const double thrust_magnitude, const double initial_arg_of_periapsis, + 4 + ThrustProfileLVLH(const double t_start, const double final_arg_of_periapsis, 49 - const double satellite_eccentricity, const double satellite_a, + const double thrust_magnitude, 50 - ✗ - const double satellite_mass) { + + const double initial_arg_of_periapsis, 51 - // Thrust profile for continuous-thrust argument of periapsis change + const double satellite_eccentricity, 52 - - // Main ref: https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf + 2 + const double satellite_a, const double satellite_mass) { 53 - // + // Thrust profile for continuous-thrust argument of periapsis change 54 - // Used Eq. 67 in https://link.springer.com/article/10.1007/s10569-021-10033-9#Sec15 to determine burn angles + // Main ref: https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf 55 - ✗ - arg_of_periapsis_change_thrust_profile = true; + + // 56 - ✗ - t_start_ = t_start; + + // Used Eq. 67 in 57 - ✗ - const double alpha = M_PI/2.0; // continous thrust + + // https://link.springer.com/article/10.1007/s10569-021-10033-9#Sec15 to 58 - ✗ - (final_arg_of_periapsis > initial_arg_of_periapsis) ? sign_of_delta_omega = 1.0 : sign_of_delta_omega = -1.0; + + // determine burn angles Arguments of periapsis are input in radians 59 - ✗ - thrust_magnitude_ = thrust_magnitude; + 2 + arg_of_periapsis_change_thrust_profile = true; 60 - ✗ - const double mu_Earth = G*mass_Earth; + 2 + t_start_ = t_start; 61 - ✗ - const double delta_omega_mag = abs(final_arg_of_periapsis - initial_arg_of_periapsis); // = delta_omega / sgn(delta_omega) + 2 + const double alpha = M_PI / 2.0; // continous thrust 62 +
+ 2/2 +
+
✓ Branch 0 taken 1 times.
+
✓ Branch 1 taken 1 times.
+
+
- ✗ - const double delta_V = (2.0/3.0)*sqrt(mu_Earth/satellite_a)*satellite_eccentricity*delta_omega_mag/sqrt(1-satellite_eccentricity*satellite_eccentricity); + 2 + (final_arg_of_periapsis > initial_arg_of_periapsis) 63 - ✗ - const double acceleration = thrust_magnitude/satellite_mass; + 1 + ? sign_of_delta_omega = 1.0 64 - ✗ - t_end_ = t_start + delta_V/acceleration; + 1 + : sign_of_delta_omega = -1.0; 65 - ✗ - std::cout << "Transfer time: " << t_end_ << "\n"; + 2 + thrust_magnitude_ = thrust_magnitude; 66 - ✗ - } + 2 + const double mu_Earth = G * mass_Earth; 67 + 2 + const double delta_omega_mag = + + + 68 + + + 4 + abs(final_arg_of_periapsis - + + + 69 + + + 2 + initial_arg_of_periapsis); // = delta_omega / sgn(delta_omega) + + + 70 + + + 2 + const double delta_V = + + + 71 + + + 4 + (2.0 / 3.0) * sqrt(mu_Earth / satellite_a) * satellite_eccentricity * + + + 72 + + + 4 + delta_omega_mag / + + + 73 + + + 2 + sqrt(1 - satellite_eccentricity * satellite_eccentricity); + + + 74 + + + 2 + const double acceleration = thrust_magnitude / satellite_mass; + + + 75 + + + 2 + t_end_ = t_start + delta_V / acceleration; + + + 76 + + + 2 + std::cout << "Maneuver duration: " << t_end_ << "\n"; + + + 77 + + + 4 + } + + + 78 + + 1 bool operator==(const ThrustProfileLVLH& input_profile) { - 68 + 79
1/2 @@ -594,7 +678,7 @@

GCC Code Coverage Report

return ((t_start_ == input_profile.t_start_) && - 69 + 80
1/2 @@ -608,161 +692,161 @@

GCC Code Coverage Report

(t_end_ == input_profile.t_end_) && - 70 + 81 2 (std::equal(LVLH_force_vec_.begin(), LVLH_force_vec_.end(), - 71 + 82 1 input_profile.LVLH_force_vec_.begin()))); - 72 + 83 } - 73 + 84 }; - 74 + 85 - 75 + 86 class BodyframeTorqueProfile { - 76 + 87 public: - 77 + 88 22 double t_start_ = {0}; - 78 + 89 22 double t_end_ = {0}; - 79 + 90 22 std::array<double, 3> bodyframe_torque_list = {0, 0, 0}; - 80 + 91 42 BodyframeTorqueProfile(const double t_start, const double t_end, - 81 + 92 21 const std::array<double, 3> bodyframe_torque_vec) { - 82 + 93 21 t_start_ = t_start; - 83 + 94 21 t_end_ = t_end; - 84 + 95 21 bodyframe_torque_list = bodyframe_torque_vec; - 85 + 96 42 } - 86 + 97 2 BodyframeTorqueProfile( - 87 + 98 const double t_start, const double t_end, - 88 + 99 const std::array<double, 3> bodyframe_normalized_torque_axis_vec, - 89 + 100 1 const double input_torque_magnitude) { - 90 + 101 1 t_start_ = t_start; - 91 + 102 1 t_end_ = t_end; - 92 + 103
2/2 @@ -776,49 +860,49 @@

GCC Code Coverage Report

for (size_t ind = 0; ind < 3; ind++) { - 93 + 104 3 bodyframe_torque_list.at(ind) = - 94 + 105 3 input_torque_magnitude * bodyframe_normalized_torque_axis_vec.at(ind); - 95 + 106 3 } - 96 + 107 2 } - 97 + 108 1 bool operator==(const BodyframeTorqueProfile& input_profile) { - 98 + 109 1 return ( - 99 + 110
1/2 @@ -832,7 +916,7 @@

GCC Code Coverage Report

(t_start_ == input_profile.t_start_) && - 100 + 111
1/2 @@ -846,45 +930,45 @@

GCC Code Coverage Report

(t_end_ == input_profile.t_end_) && - 101 + 112 2 (std::equal(bodyframe_torque_list.begin(), bodyframe_torque_list.end(), - 102 + 113 1 input_profile.bodyframe_torque_list.begin()))); - 103 + 114 } - 104 + 115 }; - 105 + 116 - 106 + 117
- 5/10 + 6/12
✓ Branch 0 taken 13487189 times.
✗ Branch 1 not taken.
@@ -896,6 +980,8 @@

GCC Code Coverage Report

✗ Branch 7 not taken.
✓ Branch 8 taken 13487189 times.
✗ Branch 9 not taken.
+
✓ Branch 10 taken 13487189 times.
+
✗ Branch 11 not taken.
@@ -903,590 +989,597 @@

GCC Code Coverage Report

class Satellite { - 107 + 118 private: - 108 + 119 - 64 + 66 double inclination_ = {0}; - 109 + 120 - 64 + 66 double raan_ = { - 110 + 121 0}; // Assuming RAAN can be used interchangeably with longitude of - 111 + 122 // ascending node for the Earth-orbiting satellites simulated here - 112 + 123 - 64 + 66 double arg_of_periapsis_ = {0}; - 113 + 124 - 64 + 66 double eccentricity_ = {0}; - 114 + 125 - 64 + 66 double a_ = {0}; - 115 + 126 - 64 + 66 double true_anomaly_ = {0}; - 116 + 127 - 64 + 66 double orbital_period_ = {0}; - 117 + 128 - 64 + 66 double m_ = {1}; // default value to prevent infinities in acceleration - 118 + 129 // calculations from a=F/m - 119 + 130 // double I_={1}; //moment of inertia, taken to be same for all 3 principal - 120 + 131 // axes, set to default value for same reasons as mass - 121 + 132 - 64 + 66 double t_ = {0}; - 122 + 133 - 123 + 134 - 64 + 66 double orbital_rate_ = {0}; - 124 + 135 - 64 + 66 double orbital_angular_acceleration_ = {0}; // Time derivative of orbital - 125 + 136 // rate - 126 + 137 - 127 + 138 // Now body-frame attributes - 128 + 139 // Assuming diagonal J matrix - 129 + 140 - 64 + 66 double J_11_ = {1}; - 130 + 141 - 64 + 66 double J_22_ = {1}; - 131 + 142 - 64 + 66 double J_33_ = {1}; - 132 + 143 // The following angles are angles of the satellite body frame with respect to - 133 + 144 // the LVLH frame, represented in the body frame - 134 + 145 - 64 + 66 double pitch_angle_ = {0}; - 135 + 146 - 64 + 66 double roll_angle_ = {0}; - 136 + 147 - 64 + 66 double yaw_angle_ = {0}; - 137 + 148 - 138 + 149 // For atmospheric drag calculations - 139 + 150 // Surface area of satellite assumed to face drag conditions - 140 + 151 - 64 + 66 double A_s_ = {0}; - 141 + 152 - 142 + 153 // body-frame angular velocities relative to the LVLH frame, represented in - 143 + 154 // the body frame - 144 + 155 - 64 + 66 std::array<double, 3> body_angular_velocity_vec_wrt_LVLH_in_body_frame_ = { - 145 + 156 - 64 + 66 0, 0, 0}; - 146 + 157 - 147 + 158 // quaternion representing attitude of satellite body frame with respect to - 148 + 159 // the LVLH frame - 149 + 160 std::array<double, 4> quaternion_satellite_bodyframe_wrt_LVLH_; - 150 + 161 - 151 + 162 - 64 + 66 std::string name_ = ""; - 152 + 163 - 153 + 164 - 64 + 66 std::array<double, 3> perifocal_position_ = {0, 0, 0}; - 154 + 165 - 64 + 66 std::array<double, 3> perifocal_velocity_ = {0, 0, 0}; - 155 + 166 - 156 + 167 - 64 + 66 std::array<double, 3> ECI_position_ = {0, 0, 0}; - 157 + 168 - 64 + 66 std::array<double, 3> ECI_velocity_ = {0, 0, 0}; - 158 + 169 - 159 + 170 - 64 + 66 std::vector<ThrustProfileLVLH> thrust_profile_list_ = {}; - 160 + 171 - 64 + 66 std::vector<BodyframeTorqueProfile> bodyframe_torque_profile_list_ = {}; - 161 + 172 - 162 + 173 - 64 + 66 std::vector<std::array<double, 3>> list_of_LVLH_forces_at_this_time_ = {}; - 163 + 174 - 64 + 66 std::vector<std::array<double, 3>> list_of_ECI_forces_at_this_time_ = {}; - 164 + 175 - 64 + 66 std::vector<std::array<double, 3>> list_of_body_frame_torques_at_this_time_ = - 165 + 176 {}; - 166 + 177 - + std::vector<std::pair<std::string, std::array<double, 3>>> - 167 + 178 + + + 66 + maneuvers_awaiting_initiation_ = {}; + + + 179 - 64 + 66 double drag_surface_area = {0}; // Surface area of satellite used for - 168 + 180 // atmospheric drag calculations - 169 + 181 - 170 + 182 void initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame(); - 171 + 183 - 172 + 184 public: - 173 + 185
1/2
-
✓ Branch 0 taken 64 times.
+
✓ Branch 0 taken 66 times.
✗ Branch 1 not taken.
- 64 + 66 std::string plotting_color_ = ""; - 174 + 186 - 192 + 198 Satellite(const std::string input_file_name) { - 175 + 187 // baselining JSON input file format specifying initial orbital parameters - 176 + 188 // of satellite semimajor axis is read in units of km angles are read in - 177 + 189 // units of degrees, then internally translated to radians - 178 + 190
1/2
-
✓ Branch 0 taken 64 times.
+
✓ Branch 0 taken 66 times.
✗ Branch 1 not taken.
- 64 + 66 std::ifstream input_filestream(input_file_name); - 179 + 191
1/2
-
✓ Branch 0 taken 64 times.
+
✓ Branch 0 taken 66 times.
✗ Branch 1 not taken.
- 64 + 66 json input_data = json::parse(input_filestream); - 180 + 192 - 181 + 193
3/4
-
✓ Branch 0 taken 63 times.
+
✓ Branch 0 taken 65 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 63 times.
+
✓ Branch 2 taken 65 times.
✗ Branch 3 not taken.
- 64 + 66 inclination_ = input_data.at("Inclination"); - 182 + 194 // convert to radians - 183 + 195 - 63 + 65 inclination_ *= (M_PI / 180.0); - 184 + 196
2/2
-
✓ Branch 0 taken 62 times.
+
✓ Branch 0 taken 64 times.
✓ Branch 1 taken 1 times.
- 63 + 65 if (inclination_ == 0) { - 185 + 197
2/4 @@ -1502,259 +1595,259 @@

GCC Code Coverage Report

throw std::invalid_argument( - 186 + 198 "Zero inclination orbits are not currently supported"); - 187 + 199 } - 188 + 200 - 189 + 201
3/4
-
✓ Branch 0 taken 61 times.
+
✓ Branch 0 taken 63 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 61 times.
+
✓ Branch 2 taken 63 times.
✗ Branch 3 not taken.
- 62 + 64 raan_ = input_data.at("RAAN"); - 190 + 202 // convert to radians - 191 + 203 - 61 + 63 raan_ *= (M_PI / 180.0); - 192 + 204 - 193 + 205
3/4
-
✓ Branch 0 taken 60 times.
+
✓ Branch 0 taken 62 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 60 times.
+
✓ Branch 2 taken 62 times.
✗ Branch 3 not taken.
- 61 + 63 arg_of_periapsis_ = input_data.at("Argument of Periapsis"); - 194 + 206 // convert to radians - 195 + 207 - 60 + 62 arg_of_periapsis_ *= (M_PI / 180.0); - 196 + 208 - 197 + 209
3/4
-
✓ Branch 0 taken 59 times.
+
✓ Branch 0 taken 61 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 59 times.
+
✓ Branch 2 taken 61 times.
✗ Branch 3 not taken.
- 60 + 62 eccentricity_ = input_data.at("Eccentricity"); - 198 + 210 // If circular orbit, arg of periapsis is undefined, using convention of - 199 + 211 // setting it to 0 in this case - 200 + 212
2/2
-
✓ Branch 0 taken 45 times.
+
✓ Branch 0 taken 47 times.
✓ Branch 1 taken 14 times.
- 59 + 61 if (eccentricity_ == 0) { - 201 + 213 14 arg_of_periapsis_ = 0; - 202 + 214 14 } - 203 + 215 - 204 + 216
3/4
-
✓ Branch 0 taken 58 times.
+
✓ Branch 0 taken 60 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 58 times.
+
✓ Branch 2 taken 60 times.
✗ Branch 3 not taken.
- 59 + 61 a_ = input_data.at("Semimajor Axis"); - 205 + 217 - 58 + 60 a_ *= 1000.0; // converting from km to m - 206 + 218 - 207 + 219
3/4
-
✓ Branch 0 taken 57 times.
+
✓ Branch 0 taken 59 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 57 times.
+
✓ Branch 2 taken 59 times.
✗ Branch 3 not taken.
- 58 + 60 true_anomaly_ = input_data.at("True Anomaly"); - 208 + 220 // convert to radians - 209 + 221 - 57 + 59 true_anomaly_ *= (M_PI / 180.0); - 210 + 222 - 211 + 223 // making initial pitch angle an optional parameter - 212 + 224
4/6
-
✓ Branch 0 taken 57 times.
+
✓ Branch 0 taken 59 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 57 times.
+
✓ Branch 2 taken 59 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 8 times.
-
✓ Branch 5 taken 49 times.
+
✓ Branch 5 taken 51 times.
- 57 + 59 if (input_data.find("Initial Pitch Angle") != input_data.end()) { - 213 + 225
2/4 @@ -1770,53 +1863,53 @@

GCC Code Coverage Report

pitch_angle_ = input_data.at("Initial Pitch Angle"); - 214 + 226 // convert to radians - 215 + 227 8 pitch_angle_ *= (M_PI / 180.0); - 216 + 228 8 } - 217 + 229 // making initial roll angle an optional parameter - 218 + 230
4/6
-
✓ Branch 0 taken 57 times.
+
✓ Branch 0 taken 59 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 57 times.
+
✓ Branch 2 taken 59 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 8 times.
-
✓ Branch 5 taken 49 times.
+
✓ Branch 5 taken 51 times.
- 57 + 59 if (input_data.find("Initial Roll Angle") != input_data.end()) { - 219 + 231
2/4 @@ -1832,53 +1925,53 @@

GCC Code Coverage Report

roll_angle_ = input_data.at("Initial Roll Angle"); - 220 + 232 // convert to radians - 221 + 233 8 roll_angle_ *= (M_PI / 180.0); - 222 + 234 8 } - 223 + 235 // making initial yaw angle an optional parameter - 224 + 236
4/6
-
✓ Branch 0 taken 57 times.
+
✓ Branch 0 taken 59 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 57 times.
+
✓ Branch 2 taken 59 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 8 times.
-
✓ Branch 5 taken 49 times.
+
✓ Branch 5 taken 51 times.
- 57 + 59 if (input_data.find("Initial Yaw Angle") != input_data.end()) { - 225 + 237
2/4 @@ -1894,129 +1987,129 @@

GCC Code Coverage Report

yaw_angle_ = input_data.at("Initial Yaw Angle"); - 226 + 238 // convert to radians - 227 + 239 8 yaw_angle_ *= (M_PI / 180.0); - 228 + 240 8 } - 229 + 241 - 230 + 242
2/4
-
✓ Branch 0 taken 57 times.
+
✓ Branch 0 taken 59 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 57 times.
+
✓ Branch 2 taken 59 times.
✗ Branch 3 not taken.
- 114 + 118 initialize_and_normalize_body_quaternion(roll_angle_, pitch_angle_, - 231 + 243 - 57 + 59 yaw_angle_); - 232 + 244 - 233 + 245
3/4
-
✓ Branch 0 taken 56 times.
+
✓ Branch 0 taken 58 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 56 times.
+
✓ Branch 2 taken 58 times.
✗ Branch 3 not taken.
- 57 + 59 m_ = input_data.at("Mass"); - 234 + 246
3/4
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✓ Branch 1 taken 1 times.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
- 56 + 58 name_ = input_data.at("Name"); - 235 + 247 - 236 + 248 // Making plotting color an optional parameter - 237 + 249
4/6
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 12 times.
-
✓ Branch 5 taken 43 times.
+
✓ Branch 5 taken 45 times.
- 55 + 57 if (input_data.find("Plotting Color") != input_data.end()) { - 238 + 250
2/4 @@ -2032,53 +2125,53 @@

GCC Code Coverage Report

plotting_color_ = input_data.at("Plotting Color"); - 239 + 251 12 } - 240 + 252 - 241 + 253 // Making satellite surface area facing drag conditions an optional - 242 + 254 // parameter - 243 + 255
4/6
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 14 times.
-
✓ Branch 5 taken 41 times.
+
✓ Branch 5 taken 43 times.
- 55 + 57 if (input_data.find("A_s") != input_data.end()) { - 244 + 256
2/4 @@ -2094,193 +2187,193 @@

GCC Code Coverage Report

A_s_ = input_data.at("A_s"); - 245 + 257 14 } - 246 + 258 - 247 + 259 - 55 + 57 t_ = 0; // for now, assuming satellites are initialized at time t=0; - 248 + 260 - 249 + 261
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 orbital_period_ = calculate_orbital_period(); - 250 + 262 - 251 + 263 // updated workflow - 252 + 264
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 perifocal_position_ = calculate_perifocal_position(); - 253 + 265
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 perifocal_velocity_ = calculate_perifocal_velocity(); - 254 + 266 - 255 + 267
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 ECI_position_ = convert_perifocal_to_ECI(perifocal_position_); - 256 + 268
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 ECI_velocity_ = convert_perifocal_to_ECI(perifocal_velocity_); - 257 + 269 - 258 + 270
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 orbital_rate_ = calculate_instantaneous_orbit_rate(); - 259 + 271
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame(); - 260 + 272 // making initial omega_x an optional parameter - 261 + 273
4/6
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 8 times.
-
✓ Branch 5 taken 47 times.
+
✓ Branch 5 taken 49 times.
- 55 + 57 if (input_data.find("Initial omega_x") != input_data.end()) { - 262 + 274 8 double initial_omega_x_wrt_LVLH_in_body_frame = - 263 + 275
2/4 @@ -2296,21 +2389,21 @@

GCC Code Coverage Report

input_data.at("Initial omega_x"); - 264 + 276 // convert to radians/s - 265 + 277 8 initial_omega_x_wrt_LVLH_in_body_frame *= (M_PI / 180.0); - 266 + 278
1/2 @@ -2324,53 +2417,53 @@

GCC Code Coverage Report

body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(0) += - 267 + 279 8 initial_omega_x_wrt_LVLH_in_body_frame; - 268 + 280 8 } - 269 + 281 // making initial omega_y an optional parameter - 270 + 282
4/6
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 8 times.
-
✓ Branch 5 taken 47 times.
+
✓ Branch 5 taken 49 times.
- 55 + 57 if (input_data.find("Initial omega_y") != input_data.end()) { - 271 + 283 8 double initial_omega_y_wrt_LVLH_in_body_frame = - 272 + 284
2/4 @@ -2386,21 +2479,21 @@

GCC Code Coverage Report

input_data.at("Initial omega_y"); - 273 + 285 // convert to radians/s - 274 + 286 8 initial_omega_y_wrt_LVLH_in_body_frame *= (M_PI / 180.0); - 275 + 287
1/2 @@ -2414,60 +2507,60 @@

GCC Code Coverage Report

body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(1) += - 276 + 288 8 initial_omega_y_wrt_LVLH_in_body_frame; - 277 + 289 8 } - 278 + 290 - 279 + 291 // making initial omega_z an optional parameter - 280 + 292
4/6
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 8 times.
-
✓ Branch 5 taken 47 times.
+
✓ Branch 5 taken 49 times.
- 55 + 57 if (input_data.find("Initial omega_z") != input_data.end()) { - 281 + 293 8 double initial_omega_z_wrt_LVLH_in_body_frame = - 282 + 294
2/4 @@ -2483,21 +2576,21 @@

GCC Code Coverage Report

input_data.at("Initial omega_z"); - 283 + 295 // convert to radians/s - 284 + 296 8 initial_omega_z_wrt_LVLH_in_body_frame *= (M_PI / 180.0); - 285 + 297
1/2 @@ -2511,721 +2604,763 @@

GCC Code Coverage Report

body_angular_velocity_vec_wrt_LVLH_in_body_frame_.at(2) += - 286 + 298 8 initial_omega_z_wrt_LVLH_in_body_frame; - 287 + 299 8 } - 288 + 300 - 289 + 301 - 55 + 57 orbital_angular_acceleration_ = - 290 + 302
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 calculate_instantaneous_orbit_angular_acceleration(); - 291 + 303 - 128 + 132 } - 292 + 304 - 293 + 305 13489787 std::array<double, 3> get_ECI_position() { return ECI_position_; } - 294 + 306 std::array<double, 3> get_ECI_velocity() { return ECI_velocity_; } - 295 + 307 - 8957373 + 12476282 double get_speed() { - 296 + 308 // shouldn't matter which frame I use, might as well use perifocal coords - 297 + 309 // since it's fewer operations (no W-direction component so can omit that - 298 + 310 // term, whereas there's x,y,z components in ECI) - 299 + 311 - 17914746 + 24952564 return sqrt(pow(perifocal_velocity_.at(0), 2) + - 300 + 312 - 8957373 + 12476282 pow(perifocal_velocity_.at(1), 2)); - 301 + 313 } - 302 + 314 2 double get_speed_ECI() { - 303 + 315 4 return sqrt(pow(ECI_velocity_.at(0), 2) + pow(ECI_velocity_.at(1), 2) + - 304 + 316 2 pow(ECI_velocity_.at(2), 2)); - 305 + 317 } - 306 + 318 - 35801632 + 49877272 double get_radius() { - 307 + 319 // shouldn't matter which frame I use, might as well use perifocal coords - 308 + 320 // since it's fewer operations (no W-direction component so can omit that - 309 + 321 // term, whereas there's x,y,z components in ECI) - 310 + 322 - 71603264 + 99754544 return sqrt(pow(perifocal_position_.at(0), 2) + - 311 + 323 - 35801632 + 49877272 pow(perifocal_position_.at(1), 2)); - 312 + 324 } - 313 + 325 2 double get_radius_ECI() { - 314 + 326 4 return sqrt(pow(ECI_position_.at(0), 2) + pow(ECI_position_.at(1), 2) + - 315 + 327 2 pow(ECI_position_.at(2), 2)); - 316 + 328 } - 317 + 329 9352 double get_total_energy() { - 318 + 330 9352 double orbital_radius = get_radius(); - 319 + 331 9352 double gravitational_potential_energy = - 320 + 332 9352 -G * mass_Earth * m_ / orbital_radius; - 321 + 333 - 322 + 334 9352 double orbital_speed = get_speed(); - 323 + 335 9352 double kinetic_energy = (1.0 / 2.0) * m_ * (orbital_speed * orbital_speed); - 324 + 336 - 325 + 337 9352 return (gravitational_potential_energy + kinetic_energy); - 326 + 338 } - 327 + 339 - 2 + 4 double get_mass() { return m_; } - 328 + 340 - 22422291 + 25941200 double get_instantaneous_time() { return t_; } - 329 + 341 2737 std::string get_name() { return name_; } - 330 + 342 // void evolve_RK4(const double input_timestep); - 331 + 343 - 332 + 344 std::array<double, 3> body_frame_to_ECI( - 333 + 345 const std::array<double, 3> input_vector); - 334 + 346 - 335 + 347 std::array<double, 3> ECI_to_body_frame( - 336 + 348 const std::array<double, 3> input_vector); - 337 + 349 - 338 + 350 std::array<double, 3> calculate_perifocal_position(); - 339 + 351 - 340 + 352 std::array<double, 3> calculate_perifocal_velocity(); - 341 + 353 - 342 + 354 std::array<double, 3> convert_perifocal_to_ECI( - 343 + 355 const std::array<double, 3> input_perifocal_vec); - 344 + 356 std::array<double, 3> convert_ECI_to_perifocal( - 345 + 357 const std::array<double, 3> input_ECI_vec); - 346 + 358 - 347 + 359 // std::array<double,3> convert_LVLH_to_ECI(std::array<double,3> - 348 + 360 // input_LVLH_vec); - 349 + 361 - 350 + 362 void add_LVLH_thrust_profile( - 351 + 363 const std::array<double, 3> input_LVLH_normalized_thrust_direction, - 352 + 364 const double input_LVLH_thrust_magnitude, - 353 + 365 const double input_thrust_start_time, const double input_thrust_end_time); - 354 + 366 void add_LVLH_thrust_profile( - 355 + 367 const std::array<double, 3> input_LVLH_thrust_vector, - 356 + 368 const double input_thrust_start_time, const double input_thrust_end_time); - 357 + 369 - void add_LVLH_thrust_profile(const double input_thrust_start_time, const double final_arg_of_periapsis, + void add_LVLH_thrust_profile(const double input_thrust_start_time, - 358 + 370 - const double input_thrust_magnitude); + const double final_arg_of_periapsis, - 359 + 371 + + + + const double input_thrust_magnitude); + + + 372 void add_bodyframe_torque_profile( - 360 + 373 const std::array<double, 3> input_bodyframe_direction_unit_vec, - 361 + 374 const double input_bodyframe_torque_magnitude, - 362 + 375 const double input_torque_start_time, const double input_torque_end_time); - 363 + 376 void add_bodyframe_torque_profile( - 364 + 377 const std::array<double, 3> input_bodyframe_torque_vector, - 365 + 378 const double input_torque_start_time, const double input_torque_end_time); - 366 + 379 - 367 + 380 int update_orbital_elements_from_position_and_velocity(); - 368 + 381 std::array<double, 6> get_orbital_elements(); - 369 + 382 - 370 + 383 std::pair<double, int> evolve_RK45( - 371 + 384 const double input_epsilon, const double input_initial_timestep, - 372 + 385 const bool perturbation = true, const bool atmospheric_drag = false, - 373 + 386 std::pair<double, double> drag_elements = {}); - 374 + 387 - 375 + 388 double get_orbital_parameter(const std::string orbital_parameter_name); - 376 + 389 double calculate_instantaneous_orbit_rate(); - 377 + 390 double calculate_instantaneous_orbit_angular_acceleration(); - 378 + 391 void initialize_and_normalize_body_quaternion(const double roll_angle, - 379 + 392 const double pitch_angle, - 380 + 393 const double yaw_angle); - 381 + 394 double get_attitude_val(const std::string input_attitude_val_name); - 382 + 395 double calculate_orbital_period(); - 383 + 396 int add_arg_of_periapsis_change_thrust(); - 384 + 397 + + + + void check_for_maneuvers_to_initialize(); + + + 398 + + + + void add_maneuver(const std::string maneuver_type, + + + 399 + + + + const double maneuver_start_time, + + + 400 + + + + const double final_parameter_val, + + + 401 + + + + const double thrust_magnitude); + + + 402 }; - 385 + 403 - 386 + 404 #endif - 387 + 405 diff --git a/tests/test_coverage_detailed.functions.html b/tests/test_coverage_detailed.functions.html index 3c95629..0b0798c 100644 --- a/tests/test_coverage_detailed.functions.html +++ b/tests/test_coverage_detailed.functions.html @@ -22,7 +22,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -37,21 +37,21 @@

GCC Code Coverage Report

Lines: - 1618 - 1766 - 91.6% + 1730 + 1841 + 94.0% Functions: - 78 81 - 96.3% + 82 + 98.8% Branches: - 784 - 1321 - 59.3% + 806 + 1335 + 60.4% @@ -67,87 +67,88 @@

GCC Code Coverage Report

Call count Block coverage - BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>) (include/Satellite.h:80)called 42 times100.0% - BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>, double) (include/Satellite.h:86)called 2 times100.0% - BodyframeTorqueProfile::operator==(BodyframeTorqueProfile const&) (include/Satellite.h:97)called 1 time100.0% - LVLH_to_body_transformation_matrix_from_quaternion(std::__1::array<double, 4ul>) (src/utils.cpp:921)called 8948009 times81.0% - PhasedArrayGroundStation::PhasedArrayGroundStation(PhasedArrayGroundStation const&) (include/PhasedArrayGroundStation.h:11)called 648 times100.0% - PhasedArrayGroundStation::PhasedArrayGroundStation(double, double, double, double, int) (include/PhasedArrayGroundStation.h:28)called 10 times100.0% - PhasedArrayGroundStation::angle_to_satellite_from_normal(Satellite) (src/PhasedArrayGroundStation.cpp:34)called 8749080 times100.0% - PhasedArrayGroundStation::distance_to_satellite(Satellite) (src/PhasedArrayGroundStation.cpp:18)called 4731363 times100.0% - PhasedArrayGroundStation::generate_ECEF_position() (src/PhasedArrayGroundStation.cpp:9)called 5 times100.0% - PhasedArrayGroundStation::get_ECI_position(double) (src/PhasedArrayGroundStation.cpp:13)called 13480446 times100.0% - PhasedArrayGroundStation::num_sats_connected_at_this_time(double) (src/PhasedArrayGroundStation.cpp:70)called 8747784 times84.0% - PhasedArrayGroundStation::update_linked_sats_map(unsigned long, double, double) (src/PhasedArrayGroundStation.cpp:112)called 714942 times77.0% - PhasedArrayGroundStation::~PhasedArrayGroundStation() (include/PhasedArrayGroundStation.h:11)called 658 times100.0% - RK45_combined_orbit_position_velocity_attitude_deriv_function(std::__1::array<double, 13ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool) (src/utils.cpp:1097)called 54944076 times88.0% - RK45_deriv_function_orbit_position_and_velocity(std::__1::array<double, 6ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, double, bool, bool) (src/utils.cpp:347)called 54944076 times83.0% - RK45_satellite_body_angular_deriv_function(std::__1::array<double, 7ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (src/utils.cpp:1029)called 54944076 times87.0% - Satellite::Satellite(Satellite const&) (include/Satellite.h:106)called 26974378 times100.0% - Satellite::Satellite(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (include/Satellite.h:174)called 128 times100.0% - Satellite::add_LVLH_thrust_profile(double, double, double) (src/Satellite.cpp:280)not called0.0% - Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double) (src/Satellite.cpp:240)called 10 times100.0% - Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double, double) (src/Satellite.cpp:255)called 12 times100.0% - Satellite::add_arg_of_periapsis_change_thrust() (src/Satellite.cpp:687)called 8948009 times70.0% - Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double) (src/Satellite.cpp:561)called 10 times100.0% - Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double, double) (src/Satellite.cpp:574)called 10 times85.0% - Satellite::calculate_instantaneous_orbit_angular_acceleration() (src/Satellite.cpp:615)called 8948064 times100.0% - Satellite::calculate_instantaneous_orbit_rate() (src/Satellite.cpp:595)called 8948064 times100.0% - Satellite::calculate_orbital_period() (src/Satellite.cpp:18)called 56 times100.0% - Satellite::calculate_perifocal_position() (src/Satellite.cpp:25)called 55 times100.0% - Satellite::calculate_perifocal_velocity() (src/Satellite.cpp:44)called 55 times100.0% - Satellite::convert_ECI_to_perifocal(std::__1::array<double, 3ul>) (src/Satellite.cpp:111)called 53688054 times100.0% - Satellite::convert_perifocal_to_ECI(std::__1::array<double, 3ul>) (src/Satellite.cpp:61)called 110 times100.0% - Satellite::evolve_RK45(double, double, bool, bool, std::__1::pair<double, double>) (src/Satellite.cpp:394)called 8948009 times82.0% - Satellite::get_ECI_position() (include/Satellite.h:293)called 13489787 times100.0% - Satellite::get_attitude_val(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/Satellite.cpp:652)called 96215 times84.0% - Satellite::get_instantaneous_time() (include/Satellite.h:328)called 22422291 times100.0% - Satellite::get_mass() (include/Satellite.h:327)called 2 times100.0% - Satellite::get_name() (include/Satellite.h:329)called 2737 times100.0% - Satellite::get_orbital_elements() (src/Satellite.cpp:383)called 9 times100.0% - Satellite::get_orbital_parameter(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/Satellite.cpp:536)called 95664 times82.0% - Satellite::get_radius() (include/Satellite.h:306)called 35801632 times100.0% - Satellite::get_radius_ECI() (include/Satellite.h:313)called 2 times100.0% - Satellite::get_speed() (include/Satellite.h:295)called 8957373 times100.0% - Satellite::get_speed_ECI() (include/Satellite.h:302)called 2 times100.0% - Satellite::get_total_energy() (include/Satellite.h:317)called 9352 times100.0% - Satellite::initialize_and_normalize_body_quaternion(double, double, double) (src/Satellite.cpp:641)called 57 times100.0% - Satellite::initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame() (src/Satellite.cpp:678)called 55 times100.0% - Satellite::operator=(Satellite const&) (include/Satellite.h:106)called 2052 times100.0% - Satellite::update_orbital_elements_from_position_and_velocity() (src/Satellite.cpp:287)called 8948011 times81.0% - Satellite::~Satellite() (include/Satellite.h:106)called 26974488 times100.0% - SimParameters::SimParameters(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (include/utils.h:33)called 10 times100.0% - SimParameters::~SimParameters() (include/utils.h:20)called 10 times100.0% - ThrustProfileLVLH::ThrustProfileLVLH(double, double, double, double, double, double, double) (include/Satellite.h:47)not called0.0% - ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>) (include/Satellite.h:30)called 22 times100.0% - ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>, double) (include/Satellite.h:36)called 26 times100.0% - ThrustProfileLVLH::operator==(ThrustProfileLVLH const&) (include/Satellite.h:67)called 1 time100.0% - add_lowthrust_orbit_transfer(Satellite&, double, double, double) (src/utils.cpp:1573)called 2 times55.0% - calculate_omega_I(Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, double) (src/utils.cpp:1074)called 8948009 times100.0% - calculate_orbital_acceleration(std::__1::array<double, 3ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, std::__1::array<double, 3ul>, double, double, double, double, double, double, double, bool, bool) (src/utils.cpp:155)called 54944076 times97.0% - calculate_spacecraft_bodyframe_angular_acceleration(Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (src/utils.cpp:942)called 54944076 times100.0% - calibrate_mean_val(Satellite, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:1617)not called0.0% - construct_J_matrix(double, double, double) (src/utils.cpp:1087)called 8948009 times100.0% - convert_ECEF_to_ECI(Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (src/utils.cpp:1232)called 13480446 times100.0% - convert_LVLH_to_ECI_manual(std::__1::array<double, 3ul>, std::__1::array<double, 3ul>, std::__1::array<double, 3ul>) (src/utils.cpp:38)called 1939922 times75.0% - convert_array_from_LVLH_to_bodyframe(std::__1::array<double, 3ul>, double, double, double) (src/utils.cpp:1201)called 55 times100.0% - convert_cylindrical_to_cartesian(double, double, double, double) (src/utils.cpp:134)called 36697692 times100.0% - convert_lat_long_to_ECEF(double, double, double) (src/utils.cpp:1217)called 5 times100.0% - convert_quaternion_to_roll_yaw_pitch_angles(std::__1::array<double, 4ul>) (src/utils.cpp:1170)called 8948009 times100.0% - normalize_quaternion(std::__1::array<double, 4ul>) (src/utils.cpp:1158)called 8948066 times100.0% - quaternion_kinematics_equation(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 3, 1, 0, 3, 1>) (src/utils.cpp:1000)called 54944076 times77.0% - quaternion_multiplication(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 4, 1, 0, 4, 1>) (src/utils.cpp:16)called 114 times77.0% - rollyawpitch_angles_to_quaternion(double, double, double) (src/utils.cpp:905)called 57 times100.0% - rollyawpitch_bodyframe_to_LVLH_matrix(double, double, double) (src/utils.cpp:883)called 55 times100.0% - sim_and_draw_orbit_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:383)called 18 times79.0% - sim_and_plot_attitude_evolution_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:733)called 180 times82.0% - sim_and_plot_gs_connectivity_distance_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:1249)called 162 times77.0% - sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:1409)called 162 times81.0% - sim_and_plot_orbital_elem_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:555)called 162 times81.0% - std::__1::pair<std::__1::array<double, 13>, std::__1::pair<double, double>> RK45_step<13>(std::__1::array<double, 13>, double, std::__1::function<std::__1::array<double, 13> (std::__1::array<double, 13>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool)>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, bool, double, double, double) (include/utils.h:346)called 9157346 times87.0% - x_rot_matrix(double) (src/utils.cpp:722)called 55 times81.0% - y_rot_matrix(double) (src/utils.cpp:714)called 55 times81.0% - z_rot_matrix(double) (src/utils.cpp:705)called 13480501 times81.0% + BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>) (include/Satellite.h:91)called 42 times100.0% + BodyframeTorqueProfile::BodyframeTorqueProfile(double, double, std::__1::array<double, 3ul>, double) (include/Satellite.h:97)called 2 times100.0% + BodyframeTorqueProfile::operator==(BodyframeTorqueProfile const&) (include/Satellite.h:108)called 1 time100.0% + LVLH_to_body_transformation_matrix_from_quaternion(std::__1::array<double, 4ul>) (src/utils.cpp:940)called 12466918 times81.0% + PhasedArrayGroundStation::PhasedArrayGroundStation(PhasedArrayGroundStation const&) (include/PhasedArrayGroundStation.h:12)called 648 times100.0% + PhasedArrayGroundStation::PhasedArrayGroundStation(double, double, double, double, int) (include/PhasedArrayGroundStation.h:32)called 10 times100.0% + PhasedArrayGroundStation::angle_to_satellite_from_normal(Satellite) (src/PhasedArrayGroundStation.cpp:39)called 8749080 times100.0% + PhasedArrayGroundStation::distance_to_satellite(Satellite) (src/PhasedArrayGroundStation.cpp:20)called 4731363 times100.0% + PhasedArrayGroundStation::generate_ECEF_position() (src/PhasedArrayGroundStation.cpp:11)called 5 times100.0% + PhasedArrayGroundStation::get_ECI_position(double) (src/PhasedArrayGroundStation.cpp:15)called 13480446 times100.0% + PhasedArrayGroundStation::num_sats_connected_at_this_time(double) (src/PhasedArrayGroundStation.cpp:79)called 8747784 times84.0% + PhasedArrayGroundStation::update_linked_sats_map(unsigned long, double, double) (src/PhasedArrayGroundStation.cpp:124)called 714942 times77.0% + PhasedArrayGroundStation::~PhasedArrayGroundStation() (include/PhasedArrayGroundStation.h:12)called 658 times100.0% + RK45_combined_orbit_position_velocity_attitude_deriv_function(std::__1::array<double, 13ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool) (src/utils.cpp:1116)called 81831276 times88.0% + RK45_deriv_function_orbit_position_and_velocity(std::__1::array<double, 6ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, double, bool, bool) (src/utils.cpp:352)called 81831276 times83.0% + RK45_satellite_body_angular_deriv_function(std::__1::array<double, 7ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (src/utils.cpp:1048)called 81831276 times87.0% + Satellite::Satellite(Satellite const&) (include/Satellite.h:117)called 26974378 times100.0% + Satellite::Satellite(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (include/Satellite.h:186)called 132 times100.0% + Satellite::add_LVLH_thrust_profile(double, double, double) (src/Satellite.cpp:289)not called0.0% + Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double) (src/Satellite.cpp:249)called 10 times100.0% + Satellite::add_LVLH_thrust_profile(std::__1::array<double, 3ul>, double, double, double) (src/Satellite.cpp:264)called 3495723 times100.0% + Satellite::add_arg_of_periapsis_change_thrust() (src/Satellite.cpp:710)called 12466918 times100.0% + Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double) (src/Satellite.cpp:581)called 10 times100.0% + Satellite::add_bodyframe_torque_profile(std::__1::array<double, 3ul>, double, double, double) (src/Satellite.cpp:594)called 10 times85.0% + Satellite::add_maneuver(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, double, double, double) (src/Satellite.cpp:758)called 2 times50.0% + Satellite::calculate_instantaneous_orbit_angular_acceleration() (src/Satellite.cpp:635)called 12466975 times100.0% + Satellite::calculate_instantaneous_orbit_rate() (src/Satellite.cpp:615)called 12466975 times100.0% + Satellite::calculate_orbital_period() (src/Satellite.cpp:18)called 58 times100.0% + Satellite::calculate_perifocal_position() (src/Satellite.cpp:25)called 57 times100.0% + Satellite::calculate_perifocal_velocity() (src/Satellite.cpp:44)called 57 times100.0% + Satellite::check_for_maneuvers_to_initialize() (src/Satellite.cpp:734)called 12466918 times87.0% + Satellite::convert_ECI_to_perifocal(std::__1::array<double, 3ul>) (src/Satellite.cpp:112)called 74801508 times100.0% + Satellite::convert_perifocal_to_ECI(std::__1::array<double, 3ul>) (src/Satellite.cpp:62)called 114 times100.0% + Satellite::evolve_RK45(double, double, bool, bool, std::__1::pair<double, double>) (src/Satellite.cpp:406)called 12466918 times84.0% + Satellite::get_ECI_position() (include/Satellite.h:305)called 13489787 times100.0% + Satellite::get_attitude_val(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/Satellite.cpp:672)called 96215 times84.0% + Satellite::get_instantaneous_time() (include/Satellite.h:340)called 25941200 times100.0% + Satellite::get_mass() (include/Satellite.h:339)called 4 times100.0% + Satellite::get_name() (include/Satellite.h:341)called 2737 times100.0% + Satellite::get_orbital_elements() (src/Satellite.cpp:395)called 9 times100.0% + Satellite::get_orbital_parameter(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/Satellite.cpp:555)called 95672 times82.0% + Satellite::get_radius() (include/Satellite.h:318)called 49877272 times100.0% + Satellite::get_radius_ECI() (include/Satellite.h:325)called 2 times100.0% + Satellite::get_speed() (include/Satellite.h:307)called 12476282 times100.0% + Satellite::get_speed_ECI() (include/Satellite.h:314)called 2 times100.0% + Satellite::get_total_energy() (include/Satellite.h:329)called 9352 times100.0% + Satellite::initialize_and_normalize_body_quaternion(double, double, double) (src/Satellite.cpp:661)called 59 times100.0% + Satellite::initialize_body_angular_velocity_vec_wrt_LVLH_in_body_frame() (src/Satellite.cpp:701)called 57 times100.0% + Satellite::operator=(Satellite const&) (include/Satellite.h:117)called 2052 times100.0% + Satellite::update_orbital_elements_from_position_and_velocity() (src/Satellite.cpp:298)called 12466920 times81.0% + Satellite::~Satellite() (include/Satellite.h:117)called 26974492 times100.0% + SimParameters::SimParameters(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (include/utils.h:32)called 10 times100.0% + SimParameters::~SimParameters() (include/utils.h:19)called 10 times100.0% + ThrustProfileLVLH::ThrustProfileLVLH(double, double, double, double, double, double, double) (include/Satellite.h:48)called 4 times100.0% + ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>) (include/Satellite.h:31)called 22 times100.0% + ThrustProfileLVLH::ThrustProfileLVLH(double, double, std::__1::array<double, 3ul>, double) (include/Satellite.h:37)called 6991448 times100.0% + ThrustProfileLVLH::operator==(ThrustProfileLVLH const&) (include/Satellite.h:78)called 1 time100.0% + add_lowthrust_orbit_transfer(Satellite&, double, double, double) (src/utils.cpp:1626)called 2 times55.0% + calculate_omega_I(Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, double) (src/utils.cpp:1093)called 12466918 times100.0% + calculate_orbital_acceleration(std::__1::array<double, 3ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, std::__1::array<double, 3ul>, double, double, double, double, double, double, double, bool, bool) (src/utils.cpp:159)called 81831276 times97.0% + calculate_spacecraft_bodyframe_angular_acceleration(Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (src/utils.cpp:961)called 81831276 times100.0% + construct_J_matrix(double, double, double) (src/utils.cpp:1106)called 12466918 times100.0% + convert_ECEF_to_ECI(Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (src/utils.cpp:1252)called 13480446 times100.0% + convert_LVLH_to_ECI_manual(std::__1::array<double, 3ul>, std::__1::array<double, 3ul>, std::__1::array<double, 3ul>) (src/utils.cpp:39)called 32144804 times75.0% + convert_array_from_LVLH_to_bodyframe(std::__1::array<double, 3ul>, double, double, double) (src/utils.cpp:1220)called 57 times100.0% + convert_cylindrical_to_cartesian(double, double, double, double) (src/utils.cpp:138)called 36697704 times100.0% + convert_lat_long_to_ECEF(double, double, double) (src/utils.cpp:1234)called 5 times100.0% + convert_quaternion_to_roll_yaw_pitch_angles(std::__1::array<double, 4ul>) (src/utils.cpp:1189)called 12466918 times100.0% + normalize_quaternion(std::__1::array<double, 4ul>) (src/utils.cpp:1177)called 12466977 times100.0% + quaternion_kinematics_equation(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 3, 1, 0, 3, 1>) (src/utils.cpp:1019)called 81831276 times77.0% + quaternion_multiplication(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 4, 1, 0, 4, 1>) (src/utils.cpp:17)called 118 times77.0% + rollyawpitch_angles_to_quaternion(double, double, double) (src/utils.cpp:924)called 59 times100.0% + rollyawpitch_bodyframe_to_LVLH_matrix(double, double, double) (src/utils.cpp:902)called 57 times100.0% + sim_and_draw_orbit_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:390)called 18 times79.0% + sim_and_plot_attitude_evolution_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:749)called 180 times82.0% + sim_and_plot_gs_connectivity_distance_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:1270)called 162 times77.0% + sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:1447)called 162 times81.0% + sim_and_plot_orbital_elem_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (src/utils.cpp:567)called 162 times81.0% + std::__1::pair<std::__1::array<double, 13>, std::__1::pair<double, double>> RK45_step<13>(std::__1::array<double, 13>, double, std::__1::function<std::__1::array<double, 13> (std::__1::array<double, 13>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool)>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, bool, double, double, double) (include/utils.h:348)called 13638546 times87.0% + x_rot_matrix(double) (src/utils.cpp:739)called 57 times81.0% + y_rot_matrix(double) (src/utils.cpp:731)called 57 times81.0% + z_rot_matrix(double) (src/utils.cpp:723)called 13480503 times81.0%
diff --git a/tests/test_coverage_detailed.html b/tests/test_coverage_detailed.html index 267aefd..3e3c1b3 100644 --- a/tests/test_coverage_detailed.html +++ b/tests/test_coverage_detailed.html @@ -22,7 +22,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 Coverage: @@ -45,21 +45,21 @@

GCC Code Coverage Report

Lines: - 1618 - 1766 - 91.6% + 1730 + 1841 + 94.0% Functions: - 78 81 - 96.3% + 82 + 98.8% Branches: - 784 - 1321 - 59.3% + 806 + 1335 + 60.4% @@ -92,7 +92,7 @@

GCC Code Coverage Report

100.0 100.0% - 10 / 10 + 11 / 11 100.0% 3 / 3 50.0% @@ -105,14 +105,14 @@

GCC Code Coverage Report

include/Satellite.h - 92.7 + 100.0 - 92.7% - 179 / 193 - 95.0% - 19 / 20 - 60.8% - 107 / 176 + 100.0% + 201 / 201 + 100.0% + 20 / 20 + 61.8% + 110 / 178 @@ -140,7 +140,7 @@

GCC Code Coverage Report

98.7 98.7% - 74 / 75 + 78 / 79 100.0% 6 / 6 71.9% @@ -153,14 +153,14 @@

GCC Code Coverage Report

src/Satellite.cpp - 94.1 + 95.5 - 94.1% - 365 / 388 - 95.0% - 19 / 20 - 80.6% - 87 / 108 + 95.5% + 406 / 425 + 95.5% + 21 / 22 + 80.0% + 104 / 130 @@ -169,14 +169,14 @@

GCC Code Coverage Report

src/utils.cpp - 89.5 + 91.7 - 89.5% - 869 / 971 - 96.6% - 28 / 29 - 57.5% - 435 / 756 + 91.7% + 913 / 996 + 100.0% + 28 / 28 + 58.6% + 437 / 746 diff --git a/tests/test_coverage_detailed.utils.cpp.4d3039dff574b788948119de402ca8d9.html b/tests/test_coverage_detailed.utils.cpp.4d3039dff574b788948119de402ca8d9.html index c79b88a..6d3475f 100644 --- a/tests/test_coverage_detailed.utils.cpp.4d3039dff574b788948119de402ca8d9.html +++ b/tests/test_coverage_detailed.utils.cpp.4d3039dff574b788948119de402ca8d9.html @@ -26,7 +26,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -40,21 +40,21 @@

GCC Code Coverage Report

Lines: - 869 - 971 - 89.5% + 913 + 996 + 91.7% Functions: 28 - 29 - 96.6% + 28 + 100.0% Branches: - 435 - 756 - 57.5% + 437 + 746 + 58.6% @@ -70,35 +70,34 @@

GCC Code Coverage Report

Call count Block coverage - LVLH_to_body_transformation_matrix_from_quaternion(std::__1::array<double, 4ul>) (line 921)called 8948009 times81.0% - RK45_combined_orbit_position_velocity_attitude_deriv_function(std::__1::array<double, 13ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool) (line 1097)called 54944076 times88.0% - RK45_deriv_function_orbit_position_and_velocity(std::__1::array<double, 6ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, double, bool, bool) (line 347)called 54944076 times83.0% - RK45_satellite_body_angular_deriv_function(std::__1::array<double, 7ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (line 1029)called 54944076 times87.0% - add_lowthrust_orbit_transfer(Satellite&, double, double, double) (line 1573)called 2 times55.0% - calculate_omega_I(Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, double) (line 1074)called 8948009 times100.0% - calculate_orbital_acceleration(std::__1::array<double, 3ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, std::__1::array<double, 3ul>, double, double, double, double, double, double, double, bool, bool) (line 155)called 54944076 times97.0% - calculate_spacecraft_bodyframe_angular_acceleration(Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (line 942)called 54944076 times100.0% - calibrate_mean_val(Satellite, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 1617)not called0.0% - construct_J_matrix(double, double, double) (line 1087)called 8948009 times100.0% - convert_ECEF_to_ECI(Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (line 1232)called 13480446 times100.0% - convert_LVLH_to_ECI_manual(std::__1::array<double, 3ul>, std::__1::array<double, 3ul>, std::__1::array<double, 3ul>) (line 38)called 1939922 times75.0% - convert_array_from_LVLH_to_bodyframe(std::__1::array<double, 3ul>, double, double, double) (line 1201)called 55 times100.0% - convert_cylindrical_to_cartesian(double, double, double, double) (line 134)called 36697692 times100.0% - convert_lat_long_to_ECEF(double, double, double) (line 1217)called 5 times100.0% - convert_quaternion_to_roll_yaw_pitch_angles(std::__1::array<double, 4ul>) (line 1170)called 8948009 times100.0% - normalize_quaternion(std::__1::array<double, 4ul>) (line 1158)called 8948066 times100.0% - quaternion_kinematics_equation(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 3, 1, 0, 3, 1>) (line 1000)called 54944076 times77.0% - quaternion_multiplication(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 4, 1, 0, 4, 1>) (line 16)called 114 times77.0% - rollyawpitch_angles_to_quaternion(double, double, double) (line 905)called 57 times100.0% - rollyawpitch_bodyframe_to_LVLH_matrix(double, double, double) (line 883)called 55 times100.0% - sim_and_draw_orbit_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 383)called 18 times79.0% - sim_and_plot_attitude_evolution_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 733)called 180 times82.0% - sim_and_plot_gs_connectivity_distance_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 1249)called 162 times77.0% - sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 1409)called 162 times81.0% - sim_and_plot_orbital_elem_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 555)called 162 times81.0% - x_rot_matrix(double) (line 722)called 55 times81.0% - y_rot_matrix(double) (line 714)called 55 times81.0% - z_rot_matrix(double) (line 705)called 13480501 times81.0% + LVLH_to_body_transformation_matrix_from_quaternion(std::__1::array<double, 4ul>) (line 940)called 12466918 times81.0% + RK45_combined_orbit_position_velocity_attitude_deriv_function(std::__1::array<double, 13ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool) (line 1116)called 81831276 times88.0% + RK45_deriv_function_orbit_position_and_velocity(std::__1::array<double, 6ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, double, bool, bool) (line 352)called 81831276 times83.0% + RK45_satellite_body_angular_deriv_function(std::__1::array<double, 7ul>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (line 1048)called 81831276 times87.0% + add_lowthrust_orbit_transfer(Satellite&, double, double, double) (line 1626)called 2 times55.0% + calculate_omega_I(Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, double) (line 1093)called 12466918 times100.0% + calculate_orbital_acceleration(std::__1::array<double, 3ul>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, std::__1::array<double, 3ul>, double, double, double, double, double, double, double, bool, bool) (line 159)called 81831276 times97.0% + calculate_spacecraft_bodyframe_angular_acceleration(Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 1, 0, 3, 1>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (line 961)called 81831276 times100.0% + construct_J_matrix(double, double, double) (line 1106)called 12466918 times100.0% + convert_ECEF_to_ECI(Eigen::Matrix<double, 3, 1, 0, 3, 1>, double) (line 1252)called 13480446 times100.0% + convert_LVLH_to_ECI_manual(std::__1::array<double, 3ul>, std::__1::array<double, 3ul>, std::__1::array<double, 3ul>) (line 39)called 32144804 times75.0% + convert_array_from_LVLH_to_bodyframe(std::__1::array<double, 3ul>, double, double, double) (line 1220)called 57 times100.0% + convert_cylindrical_to_cartesian(double, double, double, double) (line 138)called 36697704 times100.0% + convert_lat_long_to_ECEF(double, double, double) (line 1234)called 5 times100.0% + convert_quaternion_to_roll_yaw_pitch_angles(std::__1::array<double, 4ul>) (line 1189)called 12466918 times100.0% + normalize_quaternion(std::__1::array<double, 4ul>) (line 1177)called 12466977 times100.0% + quaternion_kinematics_equation(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 3, 1, 0, 3, 1>) (line 1019)called 81831276 times77.0% + quaternion_multiplication(Eigen::Matrix<double, 4, 1, 0, 4, 1>, Eigen::Matrix<double, 4, 1, 0, 4, 1>) (line 17)called 118 times77.0% + rollyawpitch_angles_to_quaternion(double, double, double) (line 924)called 59 times100.0% + rollyawpitch_bodyframe_to_LVLH_matrix(double, double, double) (line 902)called 57 times100.0% + sim_and_draw_orbit_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 390)called 18 times79.0% + sim_and_plot_attitude_evolution_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 749)called 180 times82.0% + sim_and_plot_gs_connectivity_distance_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 1270)called 162 times77.0% + sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation, std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 1447)called 162 times81.0% + sim_and_plot_orbital_elem_gnuplot(std::__1::vector<Satellite, std::__1::allocator<Satellite>>, SimParameters const&, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>, std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 567)called 162 times81.0% + x_rot_matrix(double) (line 739)called 57 times81.0% + y_rot_matrix(double) (line 731)called 57 times81.0% + z_rot_matrix(double) (line 723)called 13480503 times81.0%
@@ -117,877 +116,877 @@

GCC Code Coverage Report

- #include <Eigen/Dense> + #include "utils.h" 2 - #include <Eigen/Geometry> + 3 - #include <cmath> + #include <Eigen/Dense> 4 - #include <iostream> + #include <Eigen/Geometry> 5 - + #include <cmath> 6 - #include "Satellite.h" + #include <iostream> 7 - #include "PhasedArrayGroundStation.h" + 8 - #include "utils.h" + #include "PhasedArrayGroundStation.h" 9 - + #include "Satellite.h" 10 - using Eigen::Matrix3d; + 11 - using Eigen::Matrix4d; + using Eigen::Matrix3d; 12 - using Eigen::Quaterniond; + using Eigen::Matrix4d; 13 - using Eigen::Vector3d; + using Eigen::Quaterniond; 14 - using Eigen::Vector4d; + using Eigen::Vector3d; 15 - + using Eigen::Vector4d; 16 - 114 - Vector4d quaternion_multiplication(const Vector4d quaternion_1, + + 17 + 118 + Vector4d quaternion_multiplication(const Vector4d quaternion_1, + + + 18 + + const Vector4d quaternion_2) { - 18 + 19 // Ref: https://en.wikipedia.org/wiki/Quaternion#Scalar_and_vector_parts - 19 + 20 - 114 + 118 Vector3d quat_1_vec_component = { - 20 + 21 - 114 + 118 quaternion_1(1), quaternion_1(2), - 21 + 22 - 114 + 118 quaternion_1(3)}; // Here adopting convention that scalar part is first - 22 + 23 // element of quaternion - 23 + 24 - 228 + 236 Vector3d quat_2_vec_component = {quaternion_2(1), quaternion_2(2), - 24 + 25 - 114 + 118 quaternion_2(3)}; - 25 + 26 Vector3d vec_part_of_result = - 26 + 27 - 342 + 354 quaternion_1(0) * quat_2_vec_component + - 27 + 28 - 228 + 236 quaternion_2(0) * quat_1_vec_component + - 28 + 29 - 114 + 118 quat_1_vec_component.cross(quat_2_vec_component); - 29 + 30 - 114 + 118 Vector4d result; - 30 + 31 - 342 + 354 result << quaternion_1(0) * quaternion_2(0) - - 31 + 32
1/2
-
✓ Branch 0 taken 114 times.
+
✓ Branch 0 taken 118 times.
✗ Branch 1 not taken.
- 114 + 118 quat_1_vec_component.dot(quat_2_vec_component), - 32 + 33
5/10
-
✓ Branch 0 taken 114 times.
+
✓ Branch 0 taken 118 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 114 times.
+
✓ Branch 2 taken 118 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 114 times.
+
✓ Branch 4 taken 118 times.
✗ Branch 5 not taken.
-
✓ Branch 6 taken 114 times.
+
✓ Branch 6 taken 118 times.
✗ Branch 7 not taken.
-
✓ Branch 8 taken 114 times.
+
✓ Branch 8 taken 118 times.
✗ Branch 9 not taken.
- 228 + 236 vec_part_of_result(0), vec_part_of_result(1), vec_part_of_result(2); - 33 + 34 - 114 + 118 return result; - 34 + 35} - 35 + 36 - 36 + 37 //"manual" version, via dot products and cross products with position and - 37 + 38 // velocity vectors - 38 + 39 - 1939922 + 32144804 std::array<double, 3> convert_LVLH_to_ECI_manual( - 39 + 40 const std::array<double, 3> input_LVLH_vec, - 40 + 41 const std::array<double, 3> input_position_vec, - 41 + 42 const std::array<double, 3> input_velocity_vec) { - 42 + 43 // LVLH x-axis is defined as in the direction of motion - 43 + 44 // LVLH z-axis is defined as pointing back towards Earth, so along the - 44 + 45 // reversed direction of the position vector from the center of the Earth - 45 + 46 // y-axis determined from a cross product - 46 + 47 - 47 + 48 - 1939922 + 32144804 Vector3d ECI_unit_vec_x = {1.0, 0.0, 0.0}; - 48 + 49 - 1939922 + 32144804 Vector3d ECI_unit_vec_y = {0.0, 1.0, 0.0}; - 49 + 50 - 1939922 + 32144804 Vector3d ECI_unit_vec_z = {0.0, 0.0, 1.0}; - 50 + 51 - 51 + 52 - 1939922 + 32144804 std::array<double, 3> current_ECI_position_array = input_position_vec; - 52 + 53 - 1939922 + 32144804 Vector3d current_ECI_position_unit_vec; - 53 + 54
1/2
-
✓ Branch 0 taken 1939922 times.
+
✓ Branch 0 taken 32144804 times.
✗ Branch 1 not taken.
- 3879844 + 64289608 current_ECI_position_unit_vec << current_ECI_position_array.at(0), - 54 + 55
3/6
-
✓ Branch 0 taken 1939922 times.
+
✓ Branch 0 taken 32144804 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 1939922 times.
+
✓ Branch 2 taken 32144804 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 1939922 times.
+
✓ Branch 4 taken 32144804 times.
✗ Branch 5 not taken.
- 3879844 + 64289608 current_ECI_position_array.at(1), current_ECI_position_array.at(2); - 55 + 56 current_ECI_position_unit_vec - 56 + 57 - 1939922 + 32144804 .normalize(); // to make it actually a unit vector - 57 + 58 - 58 + 59 - 1939922 + 32144804 std::array<double, 3> current_ECI_velocity_array = input_velocity_vec; - 59 + 60 - 1939922 + 32144804 Vector3d current_ECI_velocity_unit_vec; - 60 + 61
1/2
-
✓ Branch 0 taken 1939922 times.
+
✓ Branch 0 taken 32144804 times.
✗ Branch 1 not taken.
- 3879844 + 64289608 current_ECI_velocity_unit_vec << current_ECI_velocity_array.at(0), - 61 + 62
3/6
-
✓ Branch 0 taken 1939922 times.
+
✓ Branch 0 taken 32144804 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 1939922 times.
+
✓ Branch 2 taken 32144804 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 1939922 times.
+
✓ Branch 4 taken 32144804 times.
✗ Branch 5 not taken.
- 3879844 + 64289608 current_ECI_velocity_array.at(1), current_ECI_velocity_array.at(2); - 62 + 63 - 1939922 + 32144804 current_ECI_velocity_unit_vec.normalize(); - 63 + 64 - 64 + 65 - 1939922 + 32144804 Vector3d LVLH_x_unit_vec = current_ECI_velocity_unit_vec; - 65 + 66 - 1939922 + 32144804 Vector3d LVLH_z_unit_vec = (-1) * current_ECI_position_unit_vec; - 66 + 67 - 67 + 68 - 1939922 + 32144804 Vector3d LVLH_y_unit_vec = LVLH_z_unit_vec.cross(LVLH_x_unit_vec); - 68 + 69 // Should already be normalized, just in case though - 69 + 70 - 1939922 + 32144804 LVLH_y_unit_vec.normalize(); - 70 + 71 - 71 + 72 - 5819766 + 96434412 double v_x_ECI = input_LVLH_vec.at(0) * ECI_unit_vec_x.dot(LVLH_x_unit_vec) + - 72 + 73 - 3879844 + 64289608 input_LVLH_vec.at(1) * ECI_unit_vec_x.dot(LVLH_y_unit_vec) + - 73 + 74 - 1939922 + 32144804 input_LVLH_vec.at(2) * ECI_unit_vec_x.dot(LVLH_z_unit_vec); - 74 + 75 - 75 + 76 - 5819766 + 96434412 double v_y_ECI = input_LVLH_vec.at(0) * ECI_unit_vec_y.dot(LVLH_x_unit_vec) + - 76 + 77 - 3879844 + 64289608 input_LVLH_vec.at(1) * ECI_unit_vec_y.dot(LVLH_y_unit_vec) + - 77 + 78 - 1939922 + 32144804 input_LVLH_vec.at(2) * ECI_unit_vec_y.dot(LVLH_z_unit_vec); - 78 + 79 - 79 + 80 - 5819766 + 96434412 double v_z_ECI = input_LVLH_vec.at(0) * ECI_unit_vec_z.dot(LVLH_x_unit_vec) + - 80 + 81 - 3879844 + 64289608 input_LVLH_vec.at(1) * ECI_unit_vec_z.dot(LVLH_y_unit_vec) + - 81 + 82 - 1939922 + 32144804 input_LVLH_vec.at(2) * ECI_unit_vec_z.dot(LVLH_z_unit_vec); - 82 + 83 - 83 + 84 - 1939922 + 32144804 std::array<double, 3> output_ECI_arr = {v_x_ECI, v_y_ECI, v_z_ECI}; - 84 + 85 - 1939922 + 32144804 return output_ECI_arr; - 85 + 86} - - 86 - - - - - 87 - // baselining cartesian coordinates in ECI frame + 88 - + // baselining cartesian coordinates in ECI frame 89 - // std::array<double, 3> calculate_orbital_acceleration( + 90 - // const std::array<double, 3> input_r_vec, const double input_spacecraft_mass, + // std::array<double, 3> calculate_orbital_acceleration( 91 - // const std::vector<std::array<double, 3>> + // const std::array<double, 3> input_r_vec, const double 92 - // input_vec_of_force_vectors_in_ECI) { + // input_spacecraft_mass, const std::vector<std::array<double, 3>> 93 - // // Note: this is the version used in the RK4 solver + // input_vec_of_force_vectors_in_ECI) { 94 - // // orbital acceleration = -G m_Earth/distance^3 * r_vec (just based on + // // Note: this is the version used in the RK4 solver 95 - // // rearranging F=ma with a the acceleration due to gravitational attraction + // // orbital acceleration = -G m_Earth/distance^3 * r_vec (just based on 96 - // // between satellite and Earth + // // rearranging F=ma with a the acceleration due to gravitational attraction 97 - // // https://en.wikipedia.org/wiki/Newton%27s_law_of_universal_gravitation) + // // between satellite and Earth 98 - // // going to be assuming Earth's position doesn't change for now + // // https://en.wikipedia.org/wiki/Newton%27s_law_of_universal_gravitation) 99 - // // also assuming Earth is spherical, can loosen this assumption in the future + // // going to be assuming Earth's position doesn't change for now 100 - // // note: this is in ECI frame + // // also assuming Earth is spherical, can loosen this assumption in the 101 - + // future 102 - // std::array<double, 3> acceleration_vec_due_to_gravity = + // // note: this is in ECI frame 103 - // input_r_vec; // shouldn't need to explicitly call copy function because + 104 - // // input_r_vec is passed by value not ref + // std::array<double, 3> acceleration_vec_due_to_gravity = 105 - + // input_r_vec; // shouldn't need to explicitly call copy function 106 - // // F=ma + // because 107 - // // a=F/m = (F_grav + F_ext)/m = (F_grav/m) + (F_ext/m) = -G*M_Earth/distance^3 + // // input_r_vec is passed by value not ref 108 - // // + ... + 109 - + // // F=ma 110 - // const double distance = sqrt(input_r_vec.at(0) * input_r_vec.at(0) + + // // a=F/m = (F_grav + F_ext)/m = (F_grav/m) + (F_ext/m) = 111 - // input_r_vec.at(1) * input_r_vec.at(1) + + // -G*M_Earth/distance^3 112 - // input_r_vec.at(2) * input_r_vec.at(2)); + // // + ... 113 - // const double overall_factor = -G * mass_Earth / pow(distance, 3); + 114 - + // const double distance = sqrt(input_r_vec.at(0) * input_r_vec.at(0) + 115 - // for (size_t ind = 0; ind < input_r_vec.size(); ind++) { + // input_r_vec.at(1) * input_r_vec.at(1) + 116 - // acceleration_vec_due_to_gravity.at(ind) *= overall_factor; + // input_r_vec.at(2) * input_r_vec.at(2)); 117 - // } + // const double overall_factor = -G * mass_Earth / pow(distance, 3); 118 @@ -1001,1217 +1000,1245 @@

GCC Code Coverage Report

- // // now add effects from externally-applied forces, e.g., thrusters, if any + // for (size_t ind = 0; ind < input_r_vec.size(); ind++) { 120 - // std::array<double, 3> acceleration_vec = acceleration_vec_due_to_gravity; + // acceleration_vec_due_to_gravity.at(ind) *= overall_factor; 121 - + // } 122 - // for (std::array<double, 3> external_force_vec_in_ECI : + 123 - // input_vec_of_force_vectors_in_ECI) { + // // now add effects from externally-applied forces, e.g., thrusters, if any 124 - // acceleration_vec.at(0) += + // std::array<double, 3> acceleration_vec = acceleration_vec_due_to_gravity; 125 - // (external_force_vec_in_ECI.at(0) / input_spacecraft_mass); + 126 - // acceleration_vec.at(1) += + // for (std::array<double, 3> external_force_vec_in_ECI : 127 - // (external_force_vec_in_ECI.at(1) / input_spacecraft_mass); + // input_vec_of_force_vectors_in_ECI) { 128 - // acceleration_vec.at(2) += + // acceleration_vec.at(0) += 129 - // (external_force_vec_in_ECI.at(2) / input_spacecraft_mass); + // (external_force_vec_in_ECI.at(0) / input_spacecraft_mass); 130 - // } + // acceleration_vec.at(1) += 131 - // return acceleration_vec; + // (external_force_vec_in_ECI.at(1) / input_spacecraft_mass); 132 - // } + // acceleration_vec.at(2) += 133 - + // (external_force_vec_in_ECI.at(2) / input_spacecraft_mass); 134 - 36697692 - std::array<double, 3> convert_cylindrical_to_cartesian( + + // } 135 - const double input_r_comp, const double input_theta_comp, + // return acceleration_vec; 136 - const double input_z_comp, const double input_theta) { + // } 137 - 36697692 - std::array<double, 3> output_cartesian_vec = {0, 0, 0}; + + 138 + 36697704 + std::array<double, 3> convert_cylindrical_to_cartesian( + + + 139 + + + + const double input_r_comp, const double input_theta_comp, + + + 140 + + + + const double input_z_comp, const double input_theta) { + + + 141 + + + 36697704 + std::array<double, 3> output_cartesian_vec = {0, 0, 0}; + + + 142 + + - 139 + 143 // Dot product method - 140 + 144 // See - 141 + 145 // https://en.wikipedia.org/wiki/Vector_fields_in_cylindrical_and_spherical_coordinates - 142 + 146 // for relation between unit vectors - 143 + 147 - 36697692 + 36697704 double x_comp = - 144 + 148 - 36697692 + 36697704 input_r_comp * cos(input_theta) + input_theta_comp * (-sin(input_theta)); - 145 + 149 - 36697692 + 36697704 double y_comp = - 146 + 150 - 36697692 + 36697704 input_r_comp * sin(input_theta) + input_theta_comp * (cos(input_theta)); - 147 + 151 - 36697692 + 36697704 double z_comp = input_z_comp; - 148 + 152 - 149 + 153 - 36697692 + 36697704 output_cartesian_vec.at(0) = x_comp; - 150 + 154 - 36697692 + 36697704 output_cartesian_vec.at(1) = y_comp; - 151 + 155 - 36697692 + 36697704 output_cartesian_vec.at(2) = z_comp; - 152 + 156 - 36697692 + 36697704 return output_cartesian_vec; - 153 + 157 } - 154 + 158 - 155 + 159 - 54944076 + 81831276 std::array<double, 3> calculate_orbital_acceleration( - 156 + 160 const std::array<double, 3> input_r_vec, const double input_spacecraft_mass, - 157 + 161 const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, - 158 + 162 const double input_evaluation_time, - 159 + 163 const std::array<double, 3> input_velocity_vec, - 160 + 164 const double input_inclination, const double input_arg_of_periapsis, - 161 + 165 const double input_true_anomaly, const double input_F_10, - 162 + 166 const double input_A_p, const double input_A_s, - 163 + 167 const double input_satellite_mass, const bool perturbation, - 164 + 168 const bool atmospheric_drag) { - 165 + 169 // Note: this is the version used in the RK45 solver (this has a more updated - 166 + 170 // workflow) orbital acceleration = -G m_Earth/distance^3 * r_vec (just based - 167 + 171 // on rearranging F=ma with a the acceleration due to gravitational attraction - 168 + 172 // between satellite and Earth - 169 + 173 // https://en.wikipedia.org/wiki/Newton%27s_law_of_universal_gravitation) - 170 + 174 // going to be assuming Earth's position doesn't change for now - 171 + 175 // also assuming Earth is spherical, can loosen this assumption in the future - 172 + 176 // note: this is in ECI frame (r_vec and velocity vec should also be in ECI - 173 + 177 // frame) - 174 + 178 - 175 + 179 std::array<double, 3> acceleration_vec_due_to_gravity = - 176 + 180 - 54944076 + 81831276 input_r_vec; // shouldn't need to explicitly call copy function because - 177 + 181 // input_r_vec is passed by value not ref - 178 + 182 - 179 + 183 // F=ma - 180 + 184 // a=F/m = (F_grav + F_ext)/m = (F_grav/m) + (F_ext/m) = -G*M_Earth/distance^3 - 181 + 185 // + ... - 182 + 186 - 183 + 187 - 164832228 + 245493828 const double distance = sqrt(input_r_vec.at(0) * input_r_vec.at(0) + - 184 + 188 - 109888152 + 163662552 input_r_vec.at(1) * input_r_vec.at(1) + - 185 + 189 - 54944076 + 81831276 input_r_vec.at(2) * input_r_vec.at(2)); - 186 + 190 - 54944076 + 81831276 const double overall_factor = -G * mass_Earth / pow(distance, 3); - 187 + 191 - 188 + 192
2/2
-
✓ Branch 0 taken 164832228 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 245493828 times.
+
✓ Branch 1 taken 81831276 times.
- 219776304 + 327325104 for (size_t ind = 0; ind < input_r_vec.size(); ind++) { - 189 + 193 - 164832228 + 245493828 acceleration_vec_due_to_gravity.at(ind) *= overall_factor; - 190 + 194 - 164832228 + 245493828 } - 191 + 195 - 192 + 196 - 54944076 + 81831276 std::array<double, 3> acceleration_vec = acceleration_vec_due_to_gravity; - 193 + 197 - 194 + 198 // now add effects from externally-applied forces, e.g., thrusters, if any - 195 + 199 - 196 + 200 std::vector<std::array<double, 3>> list_of_LVLH_forces_at_evaluation_time = - 197 + 201 - 54944076 + 81831276 {}; - 198 + 202 - 54944076 + 81831276 std::vector<std::array<double, 3>> list_of_ECI_forces_at_evaluation_time = {}; - 199 + 203 - 200 + 204
2/2
-
✓ Branch 0 taken 48319992 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 101916690 times.
+
✓ Branch 1 taken 81831276 times.
- 103264068 + 183747966 for (const ThrustProfileLVLH thrust_profile : - 201 + 205 - 54944076 + 81831276 input_list_of_thrust_profiles_LVLH) { - 202 + 206
- 3/4 + 4/4
-
✓ Branch 0 taken 48060569 times.
+
✓ Branch 0 taken 101657267 times.
✓ Branch 1 taken 259423 times.
-
✗ Branch 2 not taken.
-
✓ Branch 3 taken 1939912 times.
+
✓ Branch 2 taken 26709171 times.
+
✓ Branch 3 taken 28649083 times.
- 50259904 - if ((input_evaluation_time >= thrust_profile.t_start_) && + 157274944 + if ((input_evaluation_time >= thrust_profile.t_start_) && - 203 + 207
2/2
-
✓ Branch 0 taken 1939912 times.
-
✓ Branch 1 taken 46120657 times.
+
✓ Branch 0 taken 55358254 times.
+
✓ Branch 1 taken 46299013 times.
- 48060569 + 101657267 (input_evaluation_time <= thrust_profile.t_end_) && - 204 + 208 - 1939912 + 55358254 (thrust_profile.arg_of_periapsis_change_thrust_profile == false)) { - 205 + 209
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 list_of_LVLH_forces_at_evaluation_time.push_back( - 206 + 210 - 1939912 + 28649083 thrust_profile.LVLH_force_vec_); - 207 + 211
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 std::array<double, 3> ECI_thrust_vector = convert_LVLH_to_ECI_manual( - 208 + 212 - 1939912 + 28649083 thrust_profile.LVLH_force_vec_, input_r_vec, input_velocity_vec); - 209 + 213
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 list_of_ECI_forces_at_evaluation_time.push_back(ECI_thrust_vector); - 210 + 214 - 1939912 + 28649083 } - 211 + 215 } - 212 + 216 - 213 + 217
2/2
-
✓ Branch 0 taken 1939912 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 28649083 times.
+
✓ Branch 1 taken 81831276 times.
- 56883988 + 110480359 for (std::array<double, 3> external_force_vec_in_ECI : - 214 + 218 - 54944076 + 81831276 list_of_ECI_forces_at_evaluation_time) { - 215 + 219
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 acceleration_vec.at(0) += - 216 + 220
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 (external_force_vec_in_ECI.at(0) / input_spacecraft_mass); - 217 + 221
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 acceleration_vec.at(1) += - 218 + 222
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 (external_force_vec_in_ECI.at(1) / input_spacecraft_mass); - 219 + 223
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 acceleration_vec.at(2) += - 220 + 224
1/2
-
✓ Branch 0 taken 1939912 times.
+
✓ Branch 0 taken 28649083 times.
✗ Branch 1 not taken.
- 1939912 + 28649083 (external_force_vec_in_ECI.at(2) / input_spacecraft_mass); - 221 + 225 } - 222 + 226 - 223 + 227
2/2
-
✓ Branch 0 taken 36697692 times.
-
✓ Branch 1 taken 18246384 times.
+
✓ Branch 0 taken 36697704 times.
+
✓ Branch 1 taken 45133572 times.
- 54944076 + 81831276 if (perturbation) { - 224 + 228 // If accounting for J2 perturbation - 225 + 229 - 226 + 230 // Now let's add the additional acceleration components due to the J2 - 227 + 231 // perturbation Ref: - 228 + 232 // https://vatankhahghadim.github.io/AER506/Notes/6%20-%20Orbital%20Perturbations.pdf - 229 + 233 - 36697692 + 36697704 double J2 = 1.083 * pow(10, -3); - 230 + 234 - 36697692 - const double mu_Earth = G*mass_Earth; + 36697704 + const double mu_Earth = G * mass_Earth; - 231 + 235 - 36697692 - double C = + 73395408 + double C = 3 * mu_Earth * J2 * radius_Earth * radius_Earth / - 232 + 236 - 36697692 - 3 * mu_Earth * J2 * radius_Earth * radius_Earth / (2 * pow(distance, 4)); + 36697704 + (2 * pow(distance, 4)); - 233 + 237
1/2
-
✓ Branch 0 taken 36697692 times.
+
✓ Branch 0 taken 36697704 times.
✗ Branch 1 not taken.
- 36697692 + 36697704 double x = input_r_vec.at(0); - 234 + 238
1/2
-
✓ Branch 0 taken 36697692 times.
+
✓ Branch 0 taken 36697704 times.
✗ Branch 1 not taken.
- 36697692 + 36697704 double y = input_r_vec.at(1); - 235 + 239 - 36697692 + 36697704 double rho = sqrt(pow(x, 2) + pow(y, 2)); - 236 + 240 double theta; - 237 + 241 // Ref: - 238 + 242 // https://en.wikipedia.org/wiki/Cylindrical_coordinate_system#Line_and_volume_elements - 239 + 243
2/2
✓ Branch 0 taken 14214099 times.
-
✓ Branch 1 taken 22483593 times.
+
✓ Branch 1 taken 22483605 times.
- 36697692 + 36697704 if (x >= 0) { - 240 + 244 14214099 theta = asin( - 241 + 245 14214099 y / rho); // Note: here setting theta=0 even if both x and y are - 242 + 246 // zero, whereas it should technically be indeterminate, - 243 + 247 // but I'm going to assume this edge condition won't be hit - 244 + 248 // and I don't want undefined behavior - 245 + 249 14214099 } else { - 246 + 250
2/2
✓ Branch 0 taken 11762631 times.
-
✓ Branch 1 taken 10720962 times.
+
✓ Branch 1 taken 10720974 times.
- 22483593 + 22483605 if (y >= 0) { - 247 + 251 11762631 theta = -asin(y / rho) + M_PI; - 248 + 252 11762631 } else { - 249 + 253 - 10720962 + 10720974 theta = -asin(y / rho) - M_PI; - 250 + 254 } - 251 + 255 } - 252 + 256 - 253 + 257 - 36697692 + 36697704 double a_r = - 254 + 258 - 73395384 + 73395408 C * (3 * pow(sin(input_inclination), 2) * - 255 + 259 - 36697692 + 36697704 pow(sin(input_arg_of_periapsis + input_true_anomaly), 2) - - 256 + 260 1); - 257 + 261 - 73395384 + 73395408 double a_theta = -C * pow(sin(input_inclination), 2) * - 258 + 262 - 36697692 + 36697704 sin(2 * (input_arg_of_periapsis + input_true_anomaly)); - 259 + 263 - 73395384 + 73395408 double a_z = -C * sin(2 * input_inclination) * - 260 + 264 - 36697692 + 36697704 sin(input_arg_of_periapsis + input_true_anomaly); - 261 + 265 std::array<double, 3> cartesian_acceleration_components = - 262 + 266
1/2
-
✓ Branch 0 taken 36697692 times.
+
✓ Branch 0 taken 36697704 times.
✗ Branch 1 not taken.
- 36697692 + 36697704 convert_cylindrical_to_cartesian(a_r, a_theta, a_z, theta); - 263 + 267 - 264 + 268
2/2
-
✓ Branch 0 taken 36697692 times.
-
✓ Branch 1 taken 110093076 times.
+
✓ Branch 0 taken 36697704 times.
+
✓ Branch 1 taken 110093112 times.
- 146790768 + 146790816 for (size_t ind = 0; ind < 3; ind++) { - 265 + 269
2/4
-
✓ Branch 0 taken 110093076 times.
+
✓ Branch 0 taken 110093112 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 110093076 times.
+
✓ Branch 2 taken 110093112 times.
✗ Branch 3 not taken.
- 110093076 + 110093112 acceleration_vec.at(ind) += cartesian_acceleration_components.at(ind); - 266 + 270 - 110093076 + 110093112 } - 267 + 271 - 36697692 + 36697704 } - 268 + 272 - 54944076 + 81831276 double altitude = (distance - radius_Earth) / 1000.0; // km - 269 + 273
5/6
✓ Branch 0 taken 18323160 times.
-
✓ Branch 1 taken 36620916 times.
+
✓ Branch 1 taken 63508116 times.
✓ Branch 2 taken 18323160 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 178356 times.
@@ -2219,25 +2246,25 @@

GCC Code Coverage Report

- 54944076 + 81831276 if ((atmospheric_drag) && (altitude >= 140) && (altitude <= 400)) { - 270 + 274 // Refs: https://angeo.copernicus.org/articles/39/397/2021/ - 271 + 275 // https://www.spaceacademy.net.au/watch/debris/atmosmod.htm - 272 + 276
1/2 @@ -2251,7 +2278,7 @@

GCC Code Coverage Report

double speed = sqrt(pow(input_velocity_vec.at(0), 2) + - 273 + 277
1/2 @@ -2265,7 +2292,7 @@

GCC Code Coverage Report

pow(input_velocity_vec.at(1), 2) + - 274 + 278
1/2 @@ -2279,21 +2306,21 @@

GCC Code Coverage Report

pow(input_velocity_vec.at(2), 2)); - 275 + 279 // First, esimate atmospheric density - 276 + 280 178356 double rho = {0}; - 277 + 281
2/2 @@ -2307,196 +2334,196 @@

GCC Code Coverage Report

if (altitude < 180) { - 278 + 282 552 double a0 = 7.001985 * pow(10, -2); - 279 + 283 552 double a1 = -4.336216 * pow(10, -3); - 280 + 284 552 double a2 = -5.009831 * pow(10, -3); - 281 + 285 552 double a3 = 1.621827 * pow(10, -4); - 282 + 286 552 double a4 = -2.471283 * pow(10, -6); - 283 + 287 552 double a5 = 1.904383 * pow(10, -8); - 284 + 288 552 double a6 = -7.189421 * pow(10, -11); - 285 + 289 552 double a7 = 1.060067 * pow(10, -13); - 286 + 290 - 1104 - double fit_val = a0 + a1*altitude + a2*pow(altitude,2) + 1656 + double fit_val = a0 + a1 * altitude + a2 * pow(altitude, 2) + - 287 + 291 - 552 - + a3*pow(altitude,3) + a4*pow(altitude,4) + 1656 + a3 * pow(altitude, 3) + a4 * pow(altitude, 4) + - 288 + 292 - 552 - + a5*pow(altitude,5) + a6*pow(altitude,6) + 1656 + a5 * pow(altitude, 5) + a6 * pow(altitude, 6) + - 289 + 293 552 - + a7*pow(altitude,7); + a7 * pow(altitude, 7); - 290 + 294 - 291 + 295 552 rho = pow(10, fit_val); - 292 + 296 552 } else { - 293 + 297 177804 double T = 900 + 2.5 * (input_F_10 - 70) + 1.5 * input_A_p; - 294 + 298 177804 double new_mu = 27 - 0.012 * (altitude - 200); - 295 + 299 177804 double H = T / new_mu; - 296 + 300 177804 rho = 6 * pow(10, -10) * exp(-(altitude - 175) / H); - 297 + 301 } - 298 + 302 - 299 + 303 // Now estimate the satellite's ballistic coefficient B - 300 + 304 178356 double C_d = 2.2; - 301 + 305 178356 double B = C_d * input_A_s / input_satellite_mass; - 302 + 306 178356 double drag_deceleration = (1.0 / 2.0) * rho * B * pow(speed, 2); - 303 + 307 // Should act in direction directly opposite to velocity - 304 + 308 178356 std::array<double, 3> velocity_unit_vec = {0.0, 0.0, 0.0}; - 305 + 309
2/2 @@ -2510,7 +2537,7 @@

GCC Code Coverage Report

for (size_t ind = 0; ind < 3; ind++) { - 306 + 310
2/4 @@ -2526,21 +2553,21 @@

GCC Code Coverage Report

velocity_unit_vec.at(ind) = input_velocity_vec.at(ind) / speed; - 307 + 311 535068 } - 308 + 312 178356 std::array<double, 3> drag_acceleration_vec = {0.0, 0.0, 0.0}; - 309 + 313
2/2 @@ -2554,7 +2581,7 @@

GCC Code Coverage Report

for (size_t ind = 0; ind < 3; ind++) { - 310 + 314
1/2 @@ -2568,7 +2595,7 @@

GCC Code Coverage Report

drag_acceleration_vec.at(ind) = - 311 + 315
1/2 @@ -2582,28 +2609,28 @@

GCC Code Coverage Report

drag_deceleration * (-1) * velocity_unit_vec.at(ind); - 312 + 316 // Factor of (-1) because this acceleration acts in direction opposite to - 313 + 317 // velocity - 314 + 318 535068 } - 315 + 319
2/2 @@ -2617,7 +2644,7 @@

GCC Code Coverage Report

for (size_t ind = 0; ind < 3; ind++) { - 316 + 320
2/4 @@ -2633,511 +2660,532 @@

GCC Code Coverage Report

acceleration_vec.at(ind) += drag_acceleration_vec.at(ind); - 317 + 321 535068 } - 318 + 322 178356 } - 319 + 323 - 320 + 324 return acceleration_vec; - 321 + 325 - 54944076 + 81831276 } - 322 + 326 - 323 + 327 // std::array<double, 6> RK4_deriv_function_orbit_position_and_velocity( - 324 + 328 // const std::array<double, 6> input_position_and_velocity, - 325 + 329 // const double input_spacecraft_mass, - 326 + 330 // const std::vector<std::array<double, 3>> - 327 + 331 // input_vec_of_force_vectors_in_ECI) { - 328 + 332 // std::array<double, 6> derivative_of_input_y = {}; - 329 + 333 // std::array<double, 3> position_array = {}; - 330 + 334 - 331 + 335 // for (size_t ind = 0; ind < 3; ind++) { - 332 + 336 // derivative_of_input_y.at(ind) = input_position_and_velocity.at(ind + 3); - 333 + 337 // position_array.at(ind) = input_position_and_velocity.at(ind); - 334 + 338 // } - 335 + 339 - 336 + 340 // std::array<double, 3> calculated_orbital_acceleration = - 337 + 341 // calculate_orbital_acceleration(position_array, input_spacecraft_mass, - 338 + 342 // input_vec_of_force_vectors_in_ECI); - 339 + 343 - 340 + 344 // for (size_t ind = 3; ind < 6; ind++) { - 341 + 345 - // derivative_of_input_y.at(ind) = calculated_orbital_acceleration.at(ind - 3); + // derivative_of_input_y.at(ind) = calculated_orbital_acceleration.at(ind - - 342 + 346 + + + + // 3); + + + 347 // } - 343 + 348 - 344 + 349 // return derivative_of_input_y; - 345 + 350 // } - 346 + 351 - 347 + 352 - 54944076 + 81831276 std::array<double, 6> RK45_deriv_function_orbit_position_and_velocity( - 348 + 353 const std::array<double, 6> input_position_and_velocity, - 349 + 354 const double input_spacecraft_mass, - 350 + 355 const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, - 351 + 356 const double input_evaluation_time, const double input_inclination, - 352 + 357 const double input_arg_of_periapsis, const double input_true_anomaly, - 353 + 358 const double input_F_10, const double input_A_p, const double input_A_s, - 354 + 359 const double input_satellite_mass, const bool perturbation, - 355 + 360 const bool atmospheric_drag) { - 356 + 361 - 54944076 - std::array<double, 6> derivative_of_input_y = {}; + + // std::cout << "In RK45 deriv function orbit position and velocity, received - 357 + 362 - 54944076 - std::array<double, 3> position_array = {}; + + // perturbation bool: " << perturbation << "\n"; - 358 + 363 - 54944076 - std::array<double, 3> velocity_array = {}; + 81831276 + std::array<double, 6> derivative_of_input_y = {}; - 359 + 364 - - + 81831276 + std::array<double, 3> position_array = {}; - 360 + 365 + + + 81831276 + std::array<double, 3> velocity_array = {}; + + + 366 + + + + + + + 367
2/2
-
✓ Branch 0 taken 164832228 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 245493828 times.
+
✓ Branch 1 taken 81831276 times.
- 219776304 + 327325104 for (size_t ind = 0; ind < 3; ind++) { - 361 + 368 - 164832228 + 245493828 derivative_of_input_y.at(ind) = input_position_and_velocity.at(ind + 3); - 362 + 369 - 164832228 + 245493828 velocity_array.at(ind) = input_position_and_velocity.at(ind + 3); - 363 + 370 - 164832228 + 245493828 position_array.at(ind) = input_position_and_velocity.at(ind); - 364 + 371 - 164832228 + 245493828 } - 365 + 372 - 366 + 373 std::array<double, 3> calculated_orbital_acceleration = - 367 + 374
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 calculate_orbital_acceleration( - 368 + 375 - 54944076 + 81831276 position_array, input_spacecraft_mass, - 369 + 376 - 54944076 + 81831276 input_list_of_thrust_profiles_LVLH, input_evaluation_time, - 370 + 377 - 54944076 + 81831276 velocity_array, input_inclination, input_arg_of_periapsis, - 371 + 378 - 54944076 + 81831276 input_true_anomaly, input_F_10, input_A_p, input_A_s, - 372 + 379 - 54944076 + 81831276 input_satellite_mass, perturbation, atmospheric_drag); - 373 + 380 - 374 + 381
2/2
-
✓ Branch 0 taken 164832228 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 245493828 times.
+
✓ Branch 1 taken 81831276 times.
- 219776304 + 327325104 for (size_t ind = 3; ind < 6; ind++) { - 375 + 382 - 164832228 + 245493828 derivative_of_input_y.at(ind) = calculated_orbital_acceleration.at(ind - 3); - 376 + 383 - 164832228 + 245493828 } - 377 + 384 - 378 + 385 - 54944076 + 81831276 return derivative_of_input_y; - 379 + 386} - 380 + 387 - 381 + 388 // Objective: simulate the input satellites over the specified total sim time, - 382 + 389 // and visualize the resulting orbits in an interactive 3D plot using gnuplot - 383 + 390 18 void sim_and_draw_orbit_gnuplot(std::vector<Satellite> input_satellite_vector, - 384 + 391 const SimParameters& input_sim_parameters, - 385 + 392 const std::string output_file_name) { - 386 + 393
1/2 @@ -3151,42 +3199,42 @@

GCC Code Coverage Report

if (input_satellite_vector.size() < 1) { - 387 + 394 std::cout << "No input Satellite objects\n"; - 388 + 395 return; - 389 + 396 } - 390 + 397 // first, open "pipe" to gnuplot - 391 + 398 18 std::string gnuplot_arg_string = "gnuplot"; - 392 + 399
1/2 @@ -3197,24 +3245,24 @@

GCC Code Coverage Report

18 - if (input_sim_parameters.terminal_name_3D == "qt"){ + if (input_sim_parameters.terminal_name_3D == "qt") { - 393 + 400 gnuplot_arg_string += " -persist"; - 394 + 401 } - 395 + 402
1/2 @@ -3225,24 +3273,24 @@

GCC Code Coverage Report

18 - FILE *gnuplot_pipe = popen(gnuplot_arg_string.c_str(), "w"); + FILE* gnuplot_pipe = popen(gnuplot_arg_string.c_str(), "w"); - 396 + 403 - 397 + 404 // if it exists - 398 + 405
1/2 @@ -3256,14 +3304,21 @@

GCC Code Coverage Report

if (gnuplot_pipe) { - 399 + 406 + + + 36 + fprintf(gnuplot_pipe, "set terminal '%s' size 900,700 font ',14'\n", + + + 407 18 - fprintf(gnuplot_pipe, "set terminal '%s' size 900,700 font ',14'\n",input_sim_parameters.terminal_name_3D.c_str()); + input_sim_parameters.terminal_name_3D.c_str()); - 400 + 408
1/2 @@ -3277,84 +3332,91 @@

GCC Code Coverage Report

if (input_sim_parameters.terminal_name_3D == "png") { - 401 + 409 + + + 36 + fprintf(gnuplot_pipe, "set output '../%s.png'\n", + + + 410 18 - fprintf(gnuplot_pipe, "set output '../%s.png'\n",output_file_name.c_str()); + output_file_name.c_str()); - 402 + 411 18 } - 403 + 412 // formatting - 404 + 413 18 fprintf(gnuplot_pipe, "set xlabel 'x [m]' offset 0,-2\n"); - 405 + 414 18 fprintf(gnuplot_pipe, "set ylabel 'y [m]' offset -2,0\n"); - 406 + 415 18 fprintf(gnuplot_pipe, "set zlabel 'z [m]'\n"); - 407 + 416 36 fprintf(gnuplot_pipe, - 408 + 417 "set title 'Simulated orbits up to time %.2f s' offset 0,-7.5\n", - 409 + 418 18 input_sim_parameters.total_sim_time); - 410 + 419 // fprintf(gnuplot_pipe,"set view 70,1,1,1\n"); - 411 + 420 18 fprintf(gnuplot_pipe, "set view equal xyz\n"); - 412 + 421
1/2 @@ -3368,42 +3430,42 @@

GCC Code Coverage Report

if (input_sim_parameters.x_increment != 0) { - 413 + 422 ✗ - fprintf(gnuplot_pipe, "set xtics %e offset 0,-1\n",input_sim_parameters.x_increment); + fprintf(gnuplot_pipe, "set xtics %e offset 0,-1\n", - 414 + 423 ✗ - } + input_sim_parameters.x_increment); - 415 + 424 - - else { + ✗ + } else { - 416 + 425 18 fprintf(gnuplot_pipe, "set xtics offset 0,-1\n"); - 417 + 426 } - 418 + 427
1/2 @@ -3417,42 +3479,42 @@

GCC Code Coverage Report

if (input_sim_parameters.y_increment != 0) { - 419 + 428 ✗ - fprintf(gnuplot_pipe, "set ytics %e offset -1,0\n",input_sim_parameters.y_increment); + fprintf(gnuplot_pipe, "set ytics %e offset -1,0\n", - 420 + 429 ✗ - } + input_sim_parameters.y_increment); - 421 + 430 - - else { + ✗ + } else { - 422 + 431 18 fprintf(gnuplot_pipe, "set ytics offset -1,0\n"); - 423 + 432 } - 424 + 433
1/2 @@ -3466,126 +3528,126 @@

GCC Code Coverage Report

if (input_sim_parameters.z_increment != 0) { - 425 + 434 ✗ - fprintf(gnuplot_pipe, "set ztics %e\n",input_sim_parameters.z_increment); + fprintf(gnuplot_pipe, "set ztics %e\n", input_sim_parameters.z_increment); - 426 + 435 } - 427 + 436 18 fprintf(gnuplot_pipe, "unset colorbox\n"); - 428 + 437 18 fprintf(gnuplot_pipe, "set style fill transparent solid 1.0\n"); - 429 + 438 - 430 + 439 18 fprintf(gnuplot_pipe, "set key offset 0,-10\n"); - 431 + 440 18 fprintf(gnuplot_pipe, "set hidden3d front\n"); - 432 + 441 - 433 + 442 // plotting - 434 + 443 // first let's set the stage for plotting the Earth - 435 + 444 18 fprintf(gnuplot_pipe, "R_Earth=%.17g\n", radius_Earth); - 436 + 445 18 fprintf(gnuplot_pipe, "set isosamples 50,50\n"); - 437 + 446 18 fprintf(gnuplot_pipe, "set parametric\n"); - 438 + 447 18 fprintf(gnuplot_pipe, "set urange [-pi/2:pi/2]\n"); - 439 + 448 18 fprintf(gnuplot_pipe, "set vrange [0:2*pi]\n"); - 440 + 449 - 441 + 450 // first satellite - 442 + 451
2/4 @@ -3601,7 +3663,7 @@

GCC Code Coverage Report

Satellite current_satellite = input_satellite_vector.at(0); - 443 + 452
2/2 @@ -3615,7 +3677,7 @@

GCC Code Coverage Report

if (input_satellite_vector.size() == 1) { - 444 + 453
2/2 @@ -3629,28 +3691,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 445 + 454 3 fprintf(gnuplot_pipe, - 446 + 455 "splot '-' with lines lw 1 lc rgb '%s' title '%s' \\\n", - 447 + 456 3 current_satellite.plotting_color_.c_str(), - 448 + 457
1/2 @@ -3664,21 +3726,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 449 + 458 3 } else { - 450 + 459 3 fprintf(gnuplot_pipe, "splot '-' with lines lw 1 title '%s' \\\n", - 451 + 460
1/2 @@ -3692,42 +3754,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 452 + 461 } - 453 + 462 - 454 + 463 6 } - 455 + 464 - 456 + 465 else { - 457 + 466
2/2 @@ -3741,28 +3803,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 458 + 467 6 fprintf(gnuplot_pipe, - 459 + 468 "splot '-' with lines lw 1 lc rgb '%s' title '%s'\\\n", - 460 + 469 6 current_satellite.plotting_color_.c_str(), - 461 + 470
1/2 @@ -3776,21 +3838,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 462 + 471 6 } else { - 463 + 472 6 fprintf(gnuplot_pipe, "splot '-' with lines lw 1 title '%s'\\\n", - 464 + 473
1/2 @@ -3804,28 +3866,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 465 + 474 } - 466 + 475 } - 467 + 476 - 468 + 477
2/2 @@ -3839,14 +3901,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 1; - 469 + 478 72 satellite_index < input_satellite_vector.size(); satellite_index++) { - 470 + 479
2/4 @@ -3862,7 +3924,7 @@

GCC Code Coverage Report

current_satellite = input_satellite_vector.at(satellite_index); - 471 + 480
2/2 @@ -3876,7 +3938,7 @@

GCC Code Coverage Report

if (satellite_index < input_satellite_vector.size() - 1) { - 472 + 481
2/2 @@ -3890,28 +3952,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 473 + 482 18 fprintf(gnuplot_pipe, - 474 + 483 ",'-' with lines lw 1 lc rgb '%s' title '%s' \\\n", - 475 + 484 18 current_satellite.plotting_color_.c_str(), - 476 + 485
1/2 @@ -3925,21 +3987,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 477 + 486 18 } else { - 478 + 487 24 fprintf(gnuplot_pipe, ",'-' with lines lw 1 title '%s' \\\n", - 479 + 488
1/2 @@ -3953,42 +4015,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 480 + 489 } - 481 + 490 - 482 + 491 42 } - 483 + 492 - 484 + 493 else { - 485 + 494
2/2 @@ -4002,28 +4064,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 486 + 495 6 fprintf(gnuplot_pipe, - 487 + 496 ",'-' with lines lw 1 lc rgb '%s' title '%s'\\\n", - 488 + 497 6 current_satellite.plotting_color_.c_str(), - 489 + 498
1/2 @@ -4037,21 +4099,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 490 + 499 6 } else { - 491 + 500 6 fprintf(gnuplot_pipe, ",'-' with lines lw 1 title '%s'\\\n", - 492 + 501
1/2 @@ -4065,63 +4127,63 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 493 + 502 } - 494 + 503 } - 495 + 504 54 } - 496 + 505 18 fprintf(gnuplot_pipe, - 497 + 506 ",R_Earth*cos(u)*cos(v),R_Earth*cos(u)*sin(v),R_Earth*sin(u) " - 498 + 507 "notitle with pm3d fillcolor rgbcolor 'navy'\n"); - 499 + 508 - 500 + 509 // now the orbit data, inline, one satellite at a time - 501 + 510
1/2 @@ -4135,7 +4197,7 @@

GCC Code Coverage Report

std::cout << "Running simulation...\n"; - 502 + 511
2/2 @@ -4149,14 +4211,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 0; - 503 + 512 90 satellite_index < input_satellite_vector.size(); satellite_index++) { - 504 + 513
2/4 @@ -4172,14 +4234,14 @@

GCC Code Coverage Report

Satellite current_satellite = input_satellite_vector.at(satellite_index); - 505 + 514 std::array<double, 3> initial_position = - 506 + 515
1/2 @@ -4193,7 +4255,7 @@

GCC Code Coverage Report

current_satellite.get_ECI_position(); - 507 + 516
1/2 @@ -4207,7 +4269,7 @@

GCC Code Coverage Report

fprintf(gnuplot_pipe, "%.17g %.17g %.17g\n", initial_position.at(0), - 508 + 517
2/4 @@ -4223,42 +4285,42 @@

GCC Code Coverage Report

initial_position.at(1), initial_position.at(2)); - 509 + 518 - 510 + 519 72 std::array<double, 3> evolved_position = {}; - 511 + 520 - 512 + 521 72 double timestep_to_use = input_sim_parameters.initial_timestep_guess; - 513 + 522 72 double current_satellite_time = - 514 + 523
1/2 @@ -4272,7 +4334,7 @@

GCC Code Coverage Report

current_satellite.get_instantaneous_time(); - 515 + 524
2/2 @@ -4286,65 +4348,77 @@

GCC Code Coverage Report

while (current_satellite_time < input_sim_parameters.total_sim_time) { - 516 + 525 + + + 18544 + std::pair<double, double> drag_elements = {input_sim_parameters.F_10, + + + 526 9272 - std::pair<double, double> drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + input_sim_parameters.A_p}; - 517 + 527 std::pair<double, int> new_timestep_and_error_code = - 518 + 528
- 2/4 + 1/2
✓ Branch 0 taken 9272 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 9272 times.
-
✗ Branch 3 not taken.
- 18544 - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, + 9272 + current_satellite.evolve_RK45( - 519 + 529 9272 - input_sim_parameters.perturbation_bool, + input_sim_parameters.epsilon, timestep_to_use, - 520 + 530 9272 - input_sim_parameters.drag_bool, drag_elements); + input_sim_parameters.perturbation_bool, - 521 + 531 + + + 9272 + input_sim_parameters.drag_bool, drag_elements); + + + 532 9272 double new_timestep = new_timestep_and_error_code.first; - 522 + 533 9272 int error_code = new_timestep_and_error_code.second; - 523 + 534
1/2 @@ -4358,56 +4432,63 @@

GCC Code Coverage Report

if (error_code != 0) { - 524 + 535 ✗ - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code - 525 + 536 + + + ✗ + << " detected, halting visualization\n"; + + + 537 fprintf(gnuplot_pipe, "e\n"); - 526 + 538 fprintf(gnuplot_pipe, "exit \n"); - 527 + 539 pclose(gnuplot_pipe); - 528 + 540 return; - 529 + 541 } - 530 + 542 9272 timestep_to_use = new_timestep; - 531 + 543
1/2 @@ -4421,7 +4502,7 @@

GCC Code Coverage Report

evolved_position = current_satellite.get_ECI_position(); - 532 + 544
1/2 @@ -4435,7 +4516,7 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 533 + 545
1/2 @@ -4449,7 +4530,7 @@

GCC Code Coverage Report

fprintf(gnuplot_pipe, "%.17g %.17g %.17g\n", evolved_position.at(0), - 534 + 546
2/4 @@ -4465,21 +4546,21 @@

GCC Code Coverage Report

evolved_position.at(1), evolved_position.at(2)); - 535 + 547 } - 536 + 548 72 fprintf(gnuplot_pipe, "e\n"); - 537 + 549
1/2 @@ -4493,14 +4574,14 @@

GCC Code Coverage Report

} - 538 + 550 - 539 + 551
1/2 @@ -4511,31 +4592,31 @@

GCC Code Coverage Report

18 - if (input_sim_parameters.terminal_name_3D == "qt"){ + if (input_sim_parameters.terminal_name_3D == "qt") { - 540 + 552 fprintf(gnuplot_pipe, "pause mouse keypress\n"); - 541 + 553 } - 542 + 554 18 fprintf(gnuplot_pipe, "exit \n"); - 543 + 555
1/2 @@ -4549,7 +4630,7 @@

GCC Code Coverage Report

pclose(gnuplot_pipe); - 544 + 556
1/2 @@ -4563,14 +4644,14 @@

GCC Code Coverage Report

std::cout << "Done\n"; - 545 + 557 - 546 + 558
1/2 @@ -4584,98 +4665,91 @@

GCC Code Coverage Report

} else { - 547 + 559 std::cout << "gnuplot not found"; - 548 + 560 } - 549 + 561 - 550 + 562 18 return; - 551 + 563 18 } - 552 + 564 - 553 + 565 // Objective: simulate the input satellites over the specified total sim time, - 554 + 566 // and plot a specific orbital element over time - 555 + 567 162 void sim_and_plot_orbital_elem_gnuplot( - 556 - - - - std::vector<Satellite> input_satellite_vector, - - - 557 + 568 - const SimParameters& input_sim_parameters, + std::vector<Satellite> input_satellite_vector, - 558 + 569 - std::string input_orbital_element_name, + const SimParameters& input_sim_parameters, - 559 + 570 - const std::string file_name) { + std::string input_orbital_element_name, const std::string file_name) { - 560 + 571
1/2 @@ -4689,56 +4763,56 @@

GCC Code Coverage Report

if (input_satellite_vector.size() < 1) { - 561 + 572 std::cout << "No input Satellite objects\n"; - 562 + 573 return; - 563 + 574 } - 564 + 575 - 565 + 576 // first, open "pipe" to gnuplot - 566 + 577 162 - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); - 567 + 578 // if it exists - 568 + 579
1/2 @@ -4752,35 +4826,42 @@

GCC Code Coverage Report

if (gnuplot_pipe) { - 569 + 580 162 - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, - 570 + 581 + + + + "set terminal png size 800,500 font ',14' linewidth 2\n"); + + + 582 // formatting - 571 + 583 162 - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); - 572 + 584 162 fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); - 573 + 585
2/2 @@ -4794,21 +4875,21 @@

GCC Code Coverage Report

if (input_orbital_element_name == "Semimajor Axis") { - 574 + 586 36 fprintf(gnuplot_pipe, "set ylabel '%s [m]'\n", - 575 + 587 18 input_orbital_element_name.c_str()); - 576 + 588
2/2 @@ -4822,105 +4903,112 @@

GCC Code Coverage Report

} else if (input_orbital_element_name == "Eccentricity") { - 577 + 589 36 fprintf(gnuplot_pipe, "set ylabel '%s'\n", - 578 + 590 18 input_orbital_element_name.c_str()); - 579 + 591 18 } else { - 580 + 592 252 fprintf(gnuplot_pipe, "set ylabel '%s [deg]'\n", - 581 + 593 126 input_orbital_element_name.c_str()); - 582 + 594 } - 583 + 595 324 fprintf(gnuplot_pipe, "set title '%s simulated up to time %.2f s'\n", - 584 + 596 162 - input_orbital_element_name.c_str(), input_sim_parameters.total_sim_time); + input_orbital_element_name.c_str(), - 585 + 597 + + + 162 + input_sim_parameters.total_sim_time); + + + 598 162 fprintf(gnuplot_pipe, "set key right bottom\n"); - 586 + 599 - 587 + 600 // plotting - 588 + 601 - 589 + 602 // first satellite - 590 + 603 162 Satellite current_satellite = input_satellite_vector.at(0); - 591 + 604
2/2 @@ -4934,7 +5022,7 @@

GCC Code Coverage Report

if (input_satellite_vector.size() == 1) { - 592 + 605
2/2 @@ -4948,28 +5036,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 593 + 606 27 fprintf(gnuplot_pipe, - 594 + 607 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \n", - 595 + 608 27 current_satellite.plotting_color_.c_str(), - 596 + 609
1/2 @@ -4983,28 +5071,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 597 + 610 27 } else { - 598 + 611 27 fprintf(gnuplot_pipe, - 599 + 612 "plot '-' using 1:2 with lines lw 1 title '%s' \n", - 600 + 613
1/2 @@ -5018,42 +5106,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 601 + 614 } - 602 + 615 - 603 + 616 54 } - 604 + 617 - 605 + 618 else { - 606 + 619
2/2 @@ -5067,28 +5155,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 607 + 620 54 fprintf(gnuplot_pipe, - 608 + 621 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\\\n", - 609 + 622 54 current_satellite.plotting_color_.c_str(), - 610 + 623
1/2 @@ -5102,28 +5190,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 611 + 624 54 } else { - 612 + 625 54 fprintf(gnuplot_pipe, - 613 + 626 "plot '-' using 1:2 with lines lw 1 title '%s'\\\n", - 614 + 627
1/2 @@ -5137,28 +5225,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 615 + 628 } - 616 + 629 } - 617 + 630 - 618 + 631
2/2 @@ -5172,14 +5260,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 1; - 619 + 632 648 satellite_index < input_satellite_vector.size(); satellite_index++) { - 620 + 633
2/4 @@ -5195,7 +5283,7 @@

GCC Code Coverage Report

current_satellite = input_satellite_vector.at(satellite_index); - 621 + 634
2/2 @@ -5209,7 +5297,7 @@

GCC Code Coverage Report

if (satellite_index < input_satellite_vector.size() - 1) { - 622 + 635
2/2 @@ -5223,28 +5311,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 623 + 636 162 fprintf(gnuplot_pipe, - 624 + 637 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \\\n", - 625 + 638 162 current_satellite.plotting_color_.c_str(), - 626 + 639
1/2 @@ -5258,28 +5346,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 627 + 640 162 } else { - 628 + 641 216 fprintf(gnuplot_pipe, - 629 + 642 ",'-' using 1:2 with lines lw 1 title '%s' \\\n", - 630 + 643
1/2 @@ -5293,42 +5381,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 631 + 644 } - 632 + 645 - 633 + 646 378 } - 634 + 647 - 635 + 648 else { - 636 + 649
2/2 @@ -5342,28 +5430,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 637 + 650 54 fprintf(gnuplot_pipe, - 638 + 651 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\n", - 639 + 652 54 current_satellite.plotting_color_.c_str(), - 640 + 653
1/2 @@ -5377,21 +5465,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 641 + 654 54 } else { - 642 + 655 54 fprintf(gnuplot_pipe, ",'-' using 1:2 with lines lw 1 title '%s'\n", - 643 + 656
1/2 @@ -5405,42 +5493,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 644 + 657 } - 645 + 658 } - 646 + 659 486 } - 647 + 660 - 648 + 661 // now the orbit data, inline, one satellite at a time - 649 + 662
1/2 @@ -5454,7 +5542,7 @@

GCC Code Coverage Report

std::cout << "Running simulation...\n"; - 650 + 663
2/2 @@ -5468,14 +5556,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 0; - 651 + 664 810 satellite_index < input_satellite_vector.size(); satellite_index++) { - 652 + 665
2/4 @@ -5491,14 +5579,14 @@

GCC Code Coverage Report

Satellite current_satellite = input_satellite_vector.at(satellite_index); - 653 + 666 648 double val = - 654 + 667
2/4 @@ -5514,14 +5602,14 @@

GCC Code Coverage Report

current_satellite.get_orbital_parameter(input_orbital_element_name); - 655 + 668 648 double current_satellite_time = - 656 + 669
1/2 @@ -5535,42 +5623,42 @@

GCC Code Coverage Report

current_satellite.get_instantaneous_time(); - 657 + 670 648 fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, val); - 658 + 671 - 659 + 672 648 double evolved_val = {0}; - 660 + 673 - 661 + 674 648 double timestep_to_use = input_sim_parameters.initial_timestep_guess; - 662 + 675
1/2 @@ -5584,7 +5672,7 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 663 + 676
2/2 @@ -5598,86 +5686,112 @@

GCC Code Coverage Report

while (current_satellite_time < input_sim_parameters.total_sim_time) { - 664 + 677 - // std::cout << "========================================================\n"; + // std::cout << - 665 + 678 - // std::cout << "Running an evolve step at satellite time " << current_satellite_time << "\n"; + // "========================================================\n"; - 666 + 679 + + + + // std::cout << "Running an evolve step at satellite time " << + + + 680 + + + + // current_satellite_time << "\n"; + + + 681 + + + 166896 + std::pair<double, double> drag_elements = {input_sim_parameters.F_10, + + + 682 83448 - std::pair<double, double> drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + input_sim_parameters.A_p}; - 667 + 683 std::pair<double, int> new_timestep_and_error_code = - 668 + 684
- 2/4 + 1/2
✓ Branch 0 taken 83448 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 83448 times.
-
✗ Branch 3 not taken.
- 166896 - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, + 83448 + current_satellite.evolve_RK45( - 669 + 685 83448 - input_sim_parameters.perturbation_bool, + input_sim_parameters.epsilon, timestep_to_use, - 670 + 686 83448 - input_sim_parameters.drag_bool, drag_elements); + input_sim_parameters.perturbation_bool, - 671 + 687 + + + 83448 + input_sim_parameters.drag_bool, drag_elements); + + + 688 83448 double new_timestep = new_timestep_and_error_code.first; - 672 + 689 83448 int error_code = new_timestep_and_error_code.second; - 673 + 690 - 674 + 691
1/2 @@ -5691,63 +5805,70 @@

GCC Code Coverage Report

if (error_code != 0) { - 675 + 692 ✗ - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code - 676 + 693 + + + ✗ + << " detected, halting visualization\n"; + + + 694 fprintf(gnuplot_pipe, "e\n"); - 677 + 695 fprintf(gnuplot_pipe, "exit \n"); - 678 + 696 pclose(gnuplot_pipe); - 679 + 697 return; - 680 + 698 } - 681 + 699 83448 timestep_to_use = new_timestep; - 682 + 700 83448 evolved_val = - 683 + 701
2/4 @@ -5763,7 +5884,7 @@

GCC Code Coverage Report

current_satellite.get_orbital_parameter(input_orbital_element_name); - 684 + 702
1/2 @@ -5777,49 +5898,49 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 685 + 703 // printf("%.17g %.17g\n", current_satellite_time, - 686 + 704 // evolved_val); - 687 + 705 166896 fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, - 688 + 706 83448 evolved_val); - 689 + 707 } - 690 + 708 648 fprintf(gnuplot_pipe, "e\n"); - 691 + 709
1/2 @@ -5833,28 +5954,28 @@

GCC Code Coverage Report

} - 692 + 710 162 fprintf(gnuplot_pipe, "pause mouse keypress\n"); - 693 + 711 - 694 + 712 162 fprintf(gnuplot_pipe, "exit \n"); - 695 + 713
1/2 @@ -5868,7 +5989,7 @@

GCC Code Coverage Report

pclose(gnuplot_pipe); - 696 + 714
1/2 @@ -5882,14 +6003,14 @@

GCC Code Coverage Report

std::cout << "Done\n"; - 697 + 715 - 698 + 716
1/3 @@ -5904,363 +6025,337 @@

GCC Code Coverage Report

} else { - 699 + 717 std::cout << "gnuplot not found"; - 700 + 718 } - 701 + 719 - 702 + 720 162 return; - 703 + 721 162 } - 704 + 722 - 705 + 723 - 13480501 + 13480503 Matrix3d z_rot_matrix(const double input_angle) { - 706 + 724 - 13480501 + 13480503 Matrix3d z_rotation_matrix; - 707 + 725
- 3/6 + 4/8
-
✓ Branch 0 taken 13480501 times.
+
✓ Branch 0 taken 13480503 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 13480501 times.
+
✓ Branch 2 taken 13480503 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 13480501 times.
+
✓ Branch 4 taken 13480503 times.
✗ Branch 5 not taken.
+
✓ Branch 6 taken 13480503 times.
+
✗ Branch 7 not taken.
- 26961002 - z_rotation_matrix << cos(input_angle), -sin(input_angle), 0, + 26961006 + z_rotation_matrix << cos(input_angle), -sin(input_angle), 0, sin(input_angle), - 708 + 726
- 3/6 + 4/8
-
✓ Branch 0 taken 13480501 times.
+
✓ Branch 0 taken 13480503 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 13480501 times.
+
✓ Branch 2 taken 13480503 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 13480501 times.
+
✓ Branch 4 taken 13480503 times.
✗ Branch 5 not taken.
+
✓ Branch 6 taken 13480503 times.
+
✗ Branch 7 not taken.
- 13480501 - sin(input_angle),cos(input_angle), 0, - - - 709 - -
- 2/4 -
-
✓ Branch 0 taken 13480501 times.
-
✗ Branch 1 not taken.
-
✓ Branch 2 taken 13480501 times.
-
✗ Branch 3 not taken.
-
-
- - 13480501 - 0, 0, 1; + 13480503 + cos(input_angle), 0, 0, 0, 1; - 710 + 727 - 711 + 728 - 13480501 + 13480503 return z_rotation_matrix; - 712 + 729} - 713 + 730 - 714 + 731 - 55 + 57 Matrix3d y_rot_matrix(const double input_angle) { - 715 + 732 - 55 + 57 Matrix3d y_rotation_matrix; - 716 + 733
6/12
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 55 times.
+
✓ Branch 4 taken 57 times.
✗ Branch 5 not taken.
-
✓ Branch 6 taken 55 times.
+
✓ Branch 6 taken 57 times.
✗ Branch 7 not taken.
-
✓ Branch 8 taken 55 times.
+
✓ Branch 8 taken 57 times.
✗ Branch 9 not taken.
-
✓ Branch 10 taken 55 times.
+
✓ Branch 10 taken 57 times.
✗ Branch 11 not taken.
- 110 + 114 y_rotation_matrix << cos(input_angle), 0, sin(input_angle), 0, 1, 0, - 717 + 734
2/4
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
- 55 + 57 -sin(input_angle), 0, cos(input_angle); - 718 + 735 - 719 + 736 - 55 + 57 return y_rotation_matrix; - 720 + 737} - 721 + 738 - 722 + 739 - 55 + 57 Matrix3d x_rot_matrix(const double input_angle) { - 723 + 740 - 55 + 57 Matrix3d x_rotation_matrix; - 724 + 741
7/14
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 55 times.
+
✓ Branch 2 taken 57 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 55 times.
+
✓ Branch 4 taken 57 times.
✗ Branch 5 not taken.
-
✓ Branch 6 taken 55 times.
+
✓ Branch 6 taken 57 times.
✗ Branch 7 not taken.
-
✓ Branch 8 taken 55 times.
+
✓ Branch 8 taken 57 times.
✗ Branch 9 not taken.
-
✓ Branch 10 taken 55 times.
+
✓ Branch 10 taken 57 times.
✗ Branch 11 not taken.
-
✓ Branch 12 taken 55 times.
+
✓ Branch 12 taken 57 times.
✗ Branch 13 not taken.
- 110 + 114 x_rotation_matrix << 1, 0, 0, 0, cos(input_angle), -sin(input_angle), 0, - 725 + 742
1/2
-
✓ Branch 0 taken 55 times.
+
✓ Branch 0 taken 57 times.
✗ Branch 1 not taken.
- 55 + 57 sin(input_angle), cos(input_angle); - 726 + 743 - 727 + 744 - 55 + 57 return x_rotation_matrix; - 728 + 745} - 729 - - - - - - - 730 + 746 - 731 + 747 // Objective: simulate the input satellites over the specified total sim time, - 732 + 748 // and plot a specific attitude-related value over time - 733 + 749 180 void sim_and_plot_attitude_evolution_gnuplot( - 734 + 750 - std::vector<Satellite> input_satellite_vector, + std::vector<Satellite> input_satellite_vector, - 735 + 751 const SimParameters& input_sim_parameters, - 736 - - - - const std::string input_plotted_val_name, - - - 737 + 752 - const std::string file_name) { + const std::string input_plotted_val_name, const std::string file_name) { - 738 + 753
1/2 @@ -6274,56 +6369,56 @@

GCC Code Coverage Report

if (input_satellite_vector.size() < 1) { - 739 + 754 std::cout << "No input Satellite objects\n"; - 740 + 755 return; - 741 + 756 } - 742 + 757 - 743 + 758 // first, open "pipe" to gnuplot - 744 + 759 180 - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); - 745 + 760 // if it exists - 746 + 761
1/2 @@ -6337,35 +6432,42 @@

GCC Code Coverage Report

if (gnuplot_pipe) { - 747 + 762 180 - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, - 748 + 763 + + + + "set terminal png size 800,500 font ',14' linewidth 2\n"); + + + 764 // formatting - 749 + 765 180 - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); - 750 + 766 180 fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); - 751 + 767
4/4 @@ -6381,7 +6483,7 @@

GCC Code Coverage Report

if ((input_plotted_val_name == "omega_x") || - 752 + 768
2/2 @@ -6395,28 +6497,28 @@

GCC Code Coverage Report

(input_plotted_val_name == "omega_y") || - 753 + 769 144 (input_plotted_val_name == "omega_z")) { - 754 + 770 108 fprintf(gnuplot_pipe, "set ylabel '%s [deg/s]'\n", - 755 + 771 54 input_plotted_val_name.c_str()); - 756 + 772
4/4 @@ -6432,7 +6534,7 @@

GCC Code Coverage Report

} else if ((input_plotted_val_name == "Roll") || - 757 + 773
2/2 @@ -6446,112 +6548,119 @@

GCC Code Coverage Report

(input_plotted_val_name == "Pitch") || - 758 + 774 90 (input_plotted_val_name == "Yaw")) { - 759 + 775 108 fprintf(gnuplot_pipe, "set ylabel '%s [deg]'\n", - 760 + 776 54 input_plotted_val_name.c_str()); - 761 + 777 54 } else { - 762 + 778 144 fprintf(gnuplot_pipe, "set ylabel '%s'\n", - 763 + 779 72 input_plotted_val_name.c_str()); - 764 + 780 } - 765 + 781 360 fprintf(gnuplot_pipe, "set title '%s simulated up to time %.2f s'\n", - 766 + 782 180 - input_plotted_val_name.c_str(), input_sim_parameters.total_sim_time); + input_plotted_val_name.c_str(), - 767 + 783 + + + 180 + input_sim_parameters.total_sim_time); + + + 784 180 fprintf(gnuplot_pipe, "set key right bottom\n"); - 768 + 785 - 769 + 786 // plotting - 770 + 787 - 771 + 788 // first satellite - 772 + 789 180 Satellite current_satellite = input_satellite_vector.at(0); - 773 + 790
2/2 @@ -6565,7 +6674,7 @@

GCC Code Coverage Report

if (input_satellite_vector.size() == 1) { - 774 + 791
2/2 @@ -6579,28 +6688,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 775 + 792 30 fprintf(gnuplot_pipe, - 776 + 793 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \n", - 777 + 794 30 current_satellite.plotting_color_.c_str(), - 778 + 795
1/2 @@ -6614,28 +6723,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 779 + 796 30 } else { - 780 + 797 30 fprintf(gnuplot_pipe, - 781 + 798 "plot '-' using 1:2 with lines lw 1 title '%s' \n", - 782 + 799
1/2 @@ -6649,42 +6758,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 783 + 800 } - 784 + 801 - 785 + 802 60 } - 786 + 803 - 787 + 804 else { - 788 + 805
2/2 @@ -6698,28 +6807,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 789 + 806 60 fprintf(gnuplot_pipe, - 790 + 807 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\\\n", - 791 + 808 60 current_satellite.plotting_color_.c_str(), - 792 + 809
1/2 @@ -6733,28 +6842,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 793 + 810 60 } else { - 794 + 811 60 fprintf(gnuplot_pipe, - 795 + 812 "plot '-' using 1:2 with lines lw 1 title '%s'\\\n", - 796 + 813
1/2 @@ -6768,28 +6877,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 797 + 814 } - 798 + 815 } - 799 + 816 - 800 + 817
2/2 @@ -6803,14 +6912,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 1; - 801 + 818 720 satellite_index < input_satellite_vector.size(); satellite_index++) { - 802 + 819
2/4 @@ -6826,7 +6935,7 @@

GCC Code Coverage Report

current_satellite = input_satellite_vector.at(satellite_index); - 803 + 820
2/2 @@ -6840,7 +6949,7 @@

GCC Code Coverage Report

if (satellite_index < input_satellite_vector.size() - 1) { - 804 + 821
2/2 @@ -6854,28 +6963,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 805 + 822 180 fprintf(gnuplot_pipe, - 806 + 823 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \\\n", - 807 + 824 180 current_satellite.plotting_color_.c_str(), - 808 + 825
1/2 @@ -6889,28 +6998,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 809 + 826 180 } else { - 810 + 827 240 fprintf(gnuplot_pipe, - 811 + 828 ",'-' using 1:2 with lines lw 1 title '%s' \\\n", - 812 + 829
1/2 @@ -6924,42 +7033,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 813 + 830 } - 814 + 831 - 815 + 832 420 } - 816 + 833 - 817 + 834 else { - 818 + 835
2/2 @@ -6973,28 +7082,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 819 + 836 60 fprintf(gnuplot_pipe, - 820 + 837 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\n", - 821 + 838 60 current_satellite.plotting_color_.c_str(), - 822 + 839
1/2 @@ -7008,21 +7117,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 823 + 840 60 } else { - 824 + 841 60 fprintf(gnuplot_pipe, ",'-' using 1:2 with lines lw 1 title '%s'\n", - 825 + 842
1/2 @@ -7036,42 +7145,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 826 + 843 } - 827 + 844 } - 828 + 845 540 } - 829 + 846 - 830 + 847 // now the orbit data, inline, one satellite at a time - 831 + 848
1/2 @@ -7085,7 +7194,7 @@

GCC Code Coverage Report

std::cout << "Running simulation...\n"; - 832 + 849
2/2 @@ -7099,14 +7208,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 0; - 833 + 850 900 satellite_index < input_satellite_vector.size(); satellite_index++) { - 834 + 851
2/4 @@ -7122,7 +7231,7 @@

GCC Code Coverage Report

Satellite current_satellite = input_satellite_vector.at(satellite_index); - 835 + 852
2/4 @@ -7138,14 +7247,14 @@

GCC Code Coverage Report

double val = current_satellite.get_attitude_val(input_plotted_val_name); - 836 + 853 720 double current_satellite_time = - 837 + 854
1/2 @@ -7159,42 +7268,42 @@

GCC Code Coverage Report

current_satellite.get_instantaneous_time(); - 838 + 855 720 fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, val); - 839 + 856 - 840 + 857 720 double evolved_val = {0}; - 841 + 858 - 842 + 859 720 double timestep_to_use = input_sim_parameters.initial_timestep_guess; - 843 + 860
1/2 @@ -7208,7 +7317,7 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 844 + 861
2/2 @@ -7222,72 +7331,84 @@

GCC Code Coverage Report

while (current_satellite_time < input_sim_parameters.total_sim_time) { - 845 + 862 + + + 190980 + std::pair<double, double> drag_elements = {input_sim_parameters.F_10, + + + 863 95490 - std::pair<double, double> drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + input_sim_parameters.A_p}; - 846 + 864 std::pair<double, int> new_timestep_and_error_code = - 847 + 865
- 2/4 + 1/2
✓ Branch 0 taken 95490 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 95490 times.
-
✗ Branch 3 not taken.
- 190980 - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, + 95490 + current_satellite.evolve_RK45( - 848 + 866 95490 - input_sim_parameters.perturbation_bool, + input_sim_parameters.epsilon, timestep_to_use, - 849 + 867 95490 - input_sim_parameters.drag_bool, drag_elements); + input_sim_parameters.perturbation_bool, - 850 + 868 + + + 95490 + input_sim_parameters.drag_bool, drag_elements); + + + 869 95490 double new_timestep = new_timestep_and_error_code.first; - 851 + 870 95490 int error_code = new_timestep_and_error_code.second; - 852 + 871 - 853 + 872
1/2 @@ -7301,63 +7422,70 @@

GCC Code Coverage Report

if (error_code != 0) { - 854 + 873 ✗ - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code - 855 + 874 + + + ✗ + << " detected, halting visualization\n"; + + + 875 fprintf(gnuplot_pipe, "e\n"); - 856 + 876 fprintf(gnuplot_pipe, "exit \n"); - 857 + 877 pclose(gnuplot_pipe); - 858 + 878 return; - 859 + 879 } - 860 + 880 95490 timestep_to_use = new_timestep; - 861 + 881 95490 evolved_val = - 862 + 882
2/4 @@ -7373,7 +7501,7 @@

GCC Code Coverage Report

current_satellite.get_attitude_val(input_plotted_val_name); - 863 + 883
1/2 @@ -7387,35 +7515,35 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 864 + 884 190980 fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, - 865 + 885 95490 evolved_val); - 866 + 886 } - 867 + 887 720 fprintf(gnuplot_pipe, "e\n"); - 868 + 888
1/2 @@ -7429,28 +7557,28 @@

GCC Code Coverage Report

} - 869 + 889 180 fprintf(gnuplot_pipe, "pause mouse keypress\n"); - 870 + 890 - 871 + 891 180 fprintf(gnuplot_pipe, "exit \n"); - 872 + 892
1/2 @@ -7464,7 +7592,7 @@

GCC Code Coverage Report

pclose(gnuplot_pipe); - 873 + 893
1/2 @@ -7478,21 +7606,14 @@

GCC Code Coverage Report

std::cout << "Done\n"; - 874 - - - - - - - 875 + 894 - 876 + 895
1/3 @@ -7507,652 +7628,652 @@

GCC Code Coverage Report

} else { - 877 + 896 std::cout << "gnuplot not found"; - 878 + 897 } - 879 + 898 - 880 + 899 180 return; - 881 + 900 180 } - 882 + 901 - 883 + 902 - 55 + 57 Matrix3d rollyawpitch_bodyframe_to_LVLH_matrix(const double input_roll, - 884 + 903 const double input_pitch, - 885 + 904 const double input_yaw) { - 886 + 905 // Going off convention in - 887 + 906 // https://ntrs.nasa.gov/api/citations/19770024112/downloads/19770024112.pdf - 888 + 907 // which appears to be first rotating by pitch, then yaw, then roll - 889 + 908 // This is a convention where the rotations are performed as: v_body = - 890 + 909 // R_x(roll)R_z(yaw)R_y(pitch)v_LVLH That's an intrinsic Tait-Bryan xzy - 891 + 910 // sequence, following convention described in - 892 + 911 // https://en.wikipedia.org/wiki/Rotation_matrix To my understanding, this is - 893 + 912 // equivalent to an extrinsic Tait-Bryan yzx sequence - 894 + 913 - 895 + 914 // First going to construct LVLH_to_bodyframe matrix, then take transpose to - 896 + 915 // make it the bodyframe_to_LVLH matrix - 897 + 916 - 165 + 171 Matrix3d bodyframe_to_LVLH_matrix = x_rot_matrix(input_roll) * - 898 + 917 - 110 + 114 z_rot_matrix(input_yaw) * - 899 + 918 - 55 + 57 y_rot_matrix(input_pitch); - 900 + 919 - 55 + 57 bodyframe_to_LVLH_matrix.transpose(); - 901 + 920 - 902 + 921 - 55 + 57 return bodyframe_to_LVLH_matrix; - 903 + 922 } - 904 + 923 - 905 + 924 - 57 + 59 std::array<double, 4> rollyawpitch_angles_to_quaternion( - 906 + 925 const double input_roll, const double input_pitch, const double input_yaw) { - 907 + 926 // Refs : - 908 + 927 // https://www.euclideanspace.com/maths/geometry/rotations/conversions/eulerToQuaternion/Euler%20to%20quat.pdf - 909 + 928 // and - 910 + 929 // https://ntrs.nasa.gov/api/citations/19770024112/downloads/19770024112.pdf - 911 + 930 - 57 + 59 Vector4d q_pitch = {cos(input_pitch / 2), 0.0, sin(input_pitch / 2), 0.0}; - 912 + 931 - 57 + 59 Vector4d q_yaw = {cos(input_yaw / 2), 0.0, 0.0, sin(input_yaw / 2)}; - 913 + 932 - 57 + 59 Vector4d q_roll = {cos(input_roll / 2), sin(input_roll / 2), 0.0, 0.0}; - 914 + 933 - 57 + 59 Vector4d q_tot = quaternion_multiplication( - 915 + 934 - 57 + 59 q_roll, quaternion_multiplication(q_yaw, q_pitch)); - 916 + 935 - 114 + 118 std::array<double, 4> output_quaternion = {q_tot(0), q_tot(1), q_tot(2), - 917 + 936 - 57 + 59 q_tot(3)}; - 918 + 937 - 57 + 59 return output_quaternion; - 919 + 938 } - 920 + 939 - 921 + 940 - 8948009 + 12466918 Matrix3d LVLH_to_body_transformation_matrix_from_quaternion( - 922 + 941 const std::array<double, 4> input_bodyframe_quaternion_relative_to_LVLH) { - 923 + 942 // Ref: - 924 + 943 // https://ntrs.nasa.gov/api/citations/20240009554/downloads/Space%20Attitude%20Development%20Control.pdf - 925 + 944 // section 4.3.1 - 926 + 945 - 8948009 + 12466918 double q0 = input_bodyframe_quaternion_relative_to_LVLH.at(0); - 927 + 946 - 8948009 + 12466918 double q1 = input_bodyframe_quaternion_relative_to_LVLH.at(1); - 928 + 947 - 8948009 + 12466918 double q2 = input_bodyframe_quaternion_relative_to_LVLH.at(2); - 929 + 948 - 8948009 + 12466918 double q3 = input_bodyframe_quaternion_relative_to_LVLH.at(3); - 930 + 949 - 931 + 950 - 8948009 + 12466918 Matrix3d LVLH_to_body_mat; - 932 + 951
2/4
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 8948009 times.
+
✓ Branch 2 taken 12466918 times.
✗ Branch 3 not taken.
- 17896018 + 24933836 LVLH_to_body_mat << 2 * q0 * q0 - 1 + 2 * q1 * q1, 2 * q1 * q2 + 2 * q0 * q3, - 933 + 952
2/4
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 8948009 times.
+
✓ Branch 2 taken 12466918 times.
✗ Branch 3 not taken.
- 8948009 + 12466918 2 * q1 * q3 - 2 * q0 * q2, 2 * q1 * q2 - 2 * q0 * q3, - 934 + 953
2/4
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 8948009 times.
+
✓ Branch 2 taken 12466918 times.
✗ Branch 3 not taken.
- 8948009 + 12466918 2 * q0 * q0 - 1 + 2 * q2 * q2, 2 * q2 * q3 + 2 * q0 * q1, - 935 + 954
2/4
-
✓ Branch 0 taken 8948009 times.
+
✓ Branch 0 taken 12466918 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 8948009 times.
+
✓ Branch 2 taken 12466918 times.
✗ Branch 3 not taken.
- 8948009 + 12466918 2 * q1 * q3 + 2 * q0 * q2, 2 * q2 * q3 - 2 * q0 * q1, - 936 + 955 - 8948009 + 12466918 2 * q0 * q0 - 1 + 2 * q3 * q3; - 937 + 956 - 938 + 957 - 8948009 + 12466918 return LVLH_to_body_mat; - 939 + 958} - 940 + 959 - 941 + 960 // Objective: compute time derivatives of bodyframe angular velocities - 942 + 961 - 54944076 + 81831276 std::array<double, 3> calculate_spacecraft_bodyframe_angular_acceleration( - 943 + 962 const Matrix3d J_matrix, - 944 + 963 const std::vector<BodyframeTorqueProfile> - 945 + 964 input_bodyframe_torque_profile_list, - 946 + 965 const Vector3d input_omega_I, - 947 + 966 const double input_orbital_angular_acceleration, - 948 + 967 const Vector3d input_omega_bodyframe_wrt_LVLH_in_body_frame, - 949 + 968 const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, - 950 + 969 const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, - 951 + 970 const double input_evaluation_time) { - 952 + 971 // Using approach from - 953 + 972 // https://ntrs.nasa.gov/api/citations/20240009554/downloads/Space%20Attitude%20Development%20Control.pdf - 954 + 973 // , Ch. 4 especially Objective: calculate omega_dot in spacecraft body frame - 955 + 974 // w.r.t. the LVLH frame, expressed in the spacecraft body frame Disturbance - 956 + 975 // torques, if eventually added in, should just be more torque profiles in the - 957 + 976 // satellite object's list of torque profiles So the input_torques vector - 958 + 977 // includes both disturbance and control torques - 959 + 978 - 54944076 + 81831276 Vector3d bodyframe_torque_vec = {0, 0, 0}; - 960 + 979 - 961 + 980
2/2
✓ Branch 0 taken 45576600 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 1 taken 81831276 times.
- 100520676 + 127407876 for (const BodyframeTorqueProfile bodyframe_torque_profile : - 962 + 981 - 54944076 + 81831276 input_bodyframe_torque_profile_list) { - 963 + 982
4/4 @@ -8168,14 +8289,14 @@

GCC Code Coverage Report

if ((input_evaluation_time >= bodyframe_torque_profile.t_start_) && - 964 + 983 44255510 (input_evaluation_time <= bodyframe_torque_profile.t_end_)) { - 965 + 984
2/2 @@ -8189,2194 +8310,2194 @@

GCC Code Coverage Report

for (size_t ind = 0; ind < 3; ind++) { - 966 + 985 616800 bodyframe_torque_vec(ind) += - 967 + 986 616800 bodyframe_torque_profile.bodyframe_torque_list.at(ind); - 968 + 987 616800 } - 969 + 988 205600 } - 970 + 989 } - 971 + 990 - 972 + 991 - 54944076 + 81831276 Vector3d omega_lvlh_dot = {0, -input_orbital_angular_acceleration, 0}; - 973 + 992 - 54944076 + 81831276 Matrix3d inverted_J_matrix = J_matrix; - 974 + 993 - 54944076 + 81831276 inverted_J_matrix.inverse(); - 975 + 994 - 976 + 995 Vector3d comp1 = - 977 + 996 - 54944076 + 81831276 -inverted_J_matrix * (input_omega_I.cross(J_matrix * input_omega_I)); - 978 + 997 - 54944076 + 81831276 Vector3d comp2 = inverted_J_matrix * bodyframe_torque_vec; - 979 + 998 - 54944076 + 81831276 Vector3d comp3 = input_omega_bodyframe_wrt_LVLH_in_body_frame.cross( - 980 + 999 - 54944076 + 81831276 input_LVLH_to_bodyframe_transformation_matrix * - 981 + 1000 input_omega_LVLH_wrt_inertial_in_LVLH); - 982 + 1001 - 54944076 + 81831276 Vector3d omega_dot_vec_LVLH_wrt_inertial_in_ECI = { - 983 + 1002 - 54944076 + 81831276 0, -input_orbital_angular_acceleration, 0}; - 984 + 1003 - 54944076 + 81831276 Vector3d comp4 = -input_LVLH_to_bodyframe_transformation_matrix * - 985 + 1004 omega_dot_vec_LVLH_wrt_inertial_in_ECI; - 986 + 1005 - 987 + 1006 Vector3d angular_acceleration_bodyframe_wrt_LVLH_in_bodyframe = - 988 + 1007 - 54944076 + 81831276 comp1 + comp2 + comp3 + comp4; - 989 + 1008 std::array<double, 3> - 990 + 1009 - 54944076 + 81831276 angular_acceleration_bodyframe_wrt_LVLH_in_bodyframe_array = { - 991 + 1010 - 164832228 + 245493828 angular_acceleration_bodyframe_wrt_LVLH_in_bodyframe(0), - 992 + 1011 - 54944076 + 81831276 angular_acceleration_bodyframe_wrt_LVLH_in_bodyframe(1), - 993 + 1012 - 54944076 + 81831276 angular_acceleration_bodyframe_wrt_LVLH_in_bodyframe(2)}; - 994 + 1013 - 995 + 1014 - 54944076 + 81831276 return angular_acceleration_bodyframe_wrt_LVLH_in_bodyframe_array; - 996 + 1015 } - 997 + 1016 - 998 + 1017 // Objective: compute time derivatives of components of quaternion describing - 999 + 1018 // orientation of satellite body frame with respect to LVLH frame - 1000 + 1019 - 54944076 + 81831276 Vector4d quaternion_kinematics_equation( - 1001 + 1020 const Vector4d quaternion_of_bodyframe_relative_to_ref_frame, - 1002 + 1021 const Vector3d angular_velocity_vec_wrt_ref_frame_in_body_frame) { - 1003 + 1022 // Ref: - 1004 + 1023 // https://ntrs.nasa.gov/api/citations/20240009554/downloads/Space%20Attitude%20Development%20Control.pdf - 1005 + 1024 // Section 4.1.2 - 1006 + 1025 - 1007 + 1026 // Here assuming scalar component is first in quaternion - 1008 + 1027 - 54944076 + 81831276 Vector3d vec_component_of_quaternion = { - 1009 + 1028 - 54944076 + 81831276 quaternion_of_bodyframe_relative_to_ref_frame(1), - 1010 + 1029 - 54944076 + 81831276 quaternion_of_bodyframe_relative_to_ref_frame(2), - 1011 + 1030 - 54944076 + 81831276 quaternion_of_bodyframe_relative_to_ref_frame(3)}; - 1012 + 1031 - 54944076 + 81831276 double q_0_dot = - 1013 + 1032 - 54944076 + 81831276 (-0.5) * angular_velocity_vec_wrt_ref_frame_in_body_frame.dot( - 1014 + 1033 vec_component_of_quaternion); - 1015 + 1034 Vector3d vec_q_dot = - 1016 + 1035 - 109888152 + 163662552 (-0.5) * angular_velocity_vec_wrt_ref_frame_in_body_frame.cross( - 1017 + 1036 - 54944076 + 81831276 vec_component_of_quaternion) + - 1018 + 1037 - 54944076 + 81831276 (0.5) * quaternion_of_bodyframe_relative_to_ref_frame(0) * - 1019 + 1038 angular_velocity_vec_wrt_ref_frame_in_body_frame; - 1020 + 1039 - 1021 + 1040 - 54944076 + 81831276 Vector4d quaternion_derivative; - 1022 + 1041
6/12
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 54944076 times.
+
✓ Branch 2 taken 81831276 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 54944076 times.
+
✓ Branch 4 taken 81831276 times.
✗ Branch 5 not taken.
-
✓ Branch 6 taken 54944076 times.
+
✓ Branch 6 taken 81831276 times.
✗ Branch 7 not taken.
-
✓ Branch 8 taken 54944076 times.
+
✓ Branch 8 taken 81831276 times.
✗ Branch 9 not taken.
-
✓ Branch 10 taken 54944076 times.
+
✓ Branch 10 taken 81831276 times.
✗ Branch 11 not taken.
- 54944076 + 81831276 quaternion_derivative << q_0_dot, vec_q_dot(0), vec_q_dot(1), vec_q_dot(2); - 1023 + 1042 - 1024 + 1043 - 54944076 + 81831276 return quaternion_derivative; - 1025 + 1044} - 1026 + 1045 - 1027 + 1046 // Computes time derivative of combined satellite quaternion + angular velocity - 1028 + 1047 // vector - 1029 + 1048 - 54944076 + 81831276 std::array<double, 7> RK45_satellite_body_angular_deriv_function( - 1030 + 1049 const std::array<double, 7> combined_bodyframe_angular_array, - 1031 + 1050 const Matrix3d J_matrix, - 1032 + 1051 const std::vector<BodyframeTorqueProfile> - 1033 + 1052 input_bodyframe_torque_profile_list, - 1034 + 1053 const Vector3d input_omega_I, double input_orbital_angular_acceleration, - 1035 + 1054 const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, - 1036 + 1055 const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, - 1037 + 1056 const double input_evaluation_time) { - 1038 + 1057 // Setting this up for an RK45 step with - 1039 + 1058 // y={q_0,q_1,q_2,q_3,omega_1,omega_2,omega_3} Objective is to produce dy/dt - 1040 + 1059 // Input quaternion should be quaternion of bodyframe relative to LVLH - 1041 + 1060 - 54944076 + 81831276 std::array<double, 7> combined_angular_derivative_array = {0, 0, 0, 0, - 1042 + 1061 0, 0, 0}; - 1043 + 1062 - 109888152 + 163662552 Vector4d quaternion = {combined_bodyframe_angular_array.at(0), - 1044 + 1063 - 54944076 + 81831276 combined_bodyframe_angular_array.at(1), - 1045 + 1064 - 54944076 + 81831276 combined_bodyframe_angular_array.at(2), - 1046 + 1065 - 54944076 + 81831276 combined_bodyframe_angular_array.at(3)}; - 1047 + 1066 - 54944076 + 81831276 Vector3d body_angular_velocity_vec_wrt_LVLH_in_body_frame = { - 1048 + 1067 - 54944076 + 81831276 combined_bodyframe_angular_array.at(4), - 1049 + 1068 - 54944076 + 81831276 combined_bodyframe_angular_array.at(5), - 1050 + 1069 - 54944076 + 81831276 combined_bodyframe_angular_array.at(6)}; - 1051 + 1070 - 54944076 + 81831276 Vector4d quaternion_derivative = quaternion_kinematics_equation( - 1052 + 1071 - 54944076 + 81831276 quaternion, body_angular_velocity_vec_wrt_LVLH_in_body_frame); - 1053 + 1072 std::array<double, 3> body_angular_acceleration_vec_wrt_LVLH_in_body_frame = - 1054 + 1073
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 calculate_spacecraft_bodyframe_angular_acceleration( - 1055 + 1074
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 J_matrix, input_bodyframe_torque_profile_list, input_omega_I, - 1056 + 1075 - 54944076 + 81831276 input_orbital_angular_acceleration, - 1057 + 1076
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 body_angular_velocity_vec_wrt_LVLH_in_body_frame, - 1058 + 1077
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_LVLH_to_bodyframe_transformation_matrix, - 1059 + 1078
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_omega_LVLH_wrt_inertial_in_LVLH, input_evaluation_time); - 1060 + 1079 - 1061 + 1080
2/2
-
✓ Branch 0 taken 219776304 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 327325104 times.
+
✓ Branch 1 taken 81831276 times.
- 274720380 + 409156380 for (size_t ind = 0; ind < 4; ind++) { - 1062 + 1081 - 219776304 + 327325104 combined_angular_derivative_array.at(ind) = quaternion_derivative(ind); - 1063 + 1082 - 219776304 + 327325104 } - 1064 + 1083
2/2
-
✓ Branch 0 taken 164832228 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 245493828 times.
+
✓ Branch 1 taken 81831276 times.
- 219776304 + 327325104 for (size_t ind = 4; ind < 7; ind++) { - 1065 + 1084 - 164832228 + 245493828 combined_angular_derivative_array.at(ind) = - 1066 + 1085 - 164832228 + 245493828 body_angular_acceleration_vec_wrt_LVLH_in_body_frame.at(ind - 4); - 1067 + 1086 - 164832228 + 245493828 } - 1068 + 1087 - 1069 + 1088 - 54944076 + 81831276 return combined_angular_derivative_array; - 1070 + 1089} - 1071 + 1090 - 1072 + 1091 // Calculate angular velocity of spacecraft body frame with respect to - 1073 + 1092 // inertial (ECI) frame - 1074 + 1093 - 8948009 + 12466918 Vector3d calculate_omega_I( - 1075 + 1094 const Vector3d input_bodyframe_ang_vel_vector_wrt_lvlh, - 1076 + 1095 const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, - 1077 + 1096 const double input_orbital_rate) { - 1078 + 1097 // Eq. 4.17 in - 1079 + 1098 // https://ntrs.nasa.gov/api/citations/20240009554/downloads/Space%20Attitude%20Development%20Control.pdf - 1080 + 1099 - 8948009 + 12466918 Vector3d omega_LVLH_wrt_inertial_in_LVLH = {0, -input_orbital_rate, 0}; - 1081 + 1100 - 8948009 + 12466918 Vector3d omega_I = input_bodyframe_ang_vel_vector_wrt_lvlh + - 1082 + 1101 - 8948009 + 12466918 input_LVLH_to_bodyframe_transformation_matrix * - 1083 + 1102 omega_LVLH_wrt_inertial_in_LVLH; - 1084 + 1103 - 8948009 + 12466918 return omega_I; - 1085 + 1104 } - 1086 + 1105 - 1087 + 1106 - 8948009 + 12466918 Matrix3d construct_J_matrix(const double input_Jxx, const double input_Jyy, - 1088 + 1107 const double input_Jzz) { - 1089 + 1108 - 8948009 + 12466918 Matrix3d J_matrix = Matrix3d::Zero(); - 1090 + 1109 - 8948009 + 12466918 J_matrix(0, 0) = input_Jxx; - 1091 + 1110 - 8948009 + 12466918 J_matrix(1, 1) = input_Jyy; - 1092 + 1111 - 8948009 + 12466918 J_matrix(2, 2) = input_Jzz; - 1093 + 1112 - 8948009 + 12466918 return J_matrix; - 1094 + 1113 } - 1095 + 1114 - 1096 + 1115 std::array<double, 13> - 1097 + 1116 - 54944076 + 81831276 RK45_combined_orbit_position_velocity_attitude_deriv_function( - 1098 + 1117 const std::array<double, 13> - 1099 + 1118 combined_position_velocity_bodyframe_angular_array, - 1100 + 1119 const Matrix3d J_matrix, - 1101 + 1120 const std::vector<BodyframeTorqueProfile> - 1102 + 1121 input_bodyframe_torque_profile_list, - 1103 + 1122 const Vector3d input_omega_I, double input_orbital_angular_acceleration, - 1104 + 1123 const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, - 1105 + 1124 const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, - 1106 + 1125 const double input_spacecraft_mass, - 1107 + 1126 const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, - 1108 + 1127 const double input_evaluation_time, const double input_inclination, - 1109 + 1128 const double input_arg_of_periapsis, const double input_true_anomaly, - 1110 + 1129 const double input_F_10, const double input_A_p, const double input_A_s, - 1111 + 1130 const bool perturbation, const bool atmospheric_drag) { - 1112 + 1131 // Input vector is in the form of {ECI_position, - 1113 + 1132 // ECI_velocity,bodyframe_quaternion_to_LVLH,bodyframe_omega_wrt_LVLH} - 1114 + 1133 // Objective is to output derivative of that vector - 1115 + 1134 std::array<double, 13> derivative_vec; - 1116 + 1135 std::array<double, 6> combined_position_and_velocity_array; - 1117 + 1136 std::array<double, 7> combined_angular_array; - 1118 + 1137 - 1119 + 1138
2/2
-
✓ Branch 0 taken 329664456 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 490987656 times.
+
✓ Branch 1 taken 81831276 times.
- 384608532 + 572818932 for (size_t ind = 0; ind < combined_position_and_velocity_array.size(); - 1120 + 1139 - 329664456 + 490987656 ind++) { - 1121 + 1140 - 329664456 + 490987656 combined_position_and_velocity_array.at(ind) = - 1122 + 1141 - 329664456 + 490987656 combined_position_velocity_bodyframe_angular_array.at(ind); - 1123 + 1142 - 329664456 + 490987656 } - 1124 + 1143
2/2
-
✓ Branch 0 taken 384608532 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 572818932 times.
+
✓ Branch 1 taken 81831276 times.
- 439552608 + 654650208 for (size_t ind = 0; ind < combined_angular_array.size(); ind++) { - 1125 + 1144 - 384608532 + 572818932 combined_angular_array.at(ind) = - 1126 + 1145 - 384608532 + 572818932 combined_position_velocity_bodyframe_angular_array.at( - 1127 + 1146 - 384608532 + 572818932 ind + combined_position_and_velocity_array.size()); - 1128 + 1147 - 384608532 + 572818932 } - 1129 + 1148 std::array<double, 6> orbital_position_and_velocity_derivative_array = - 1130 + 1149
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 RK45_deriv_function_orbit_position_and_velocity( - 1131 + 1150 - 54944076 + 81831276 combined_position_and_velocity_array, input_spacecraft_mass, - 1132 + 1151 - 54944076 + 81831276 input_list_of_thrust_profiles_LVLH, input_evaluation_time, - 1133 + 1152 - 54944076 + 81831276 input_inclination, input_arg_of_periapsis, input_true_anomaly, - 1134 + 1153 - 54944076 + 81831276 input_F_10, input_A_p, input_A_s, input_spacecraft_mass, perturbation, - 1135 + 1154 - 54944076 + 81831276 atmospheric_drag); - 1136 + 1155 - 1137 + 1156 std::array<double, 7> angular_derivative_array = - 1138 + 1157
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 RK45_satellite_body_angular_deriv_function( - 1139 + 1158 - 54944076 + 81831276 combined_angular_array, J_matrix, input_bodyframe_torque_profile_list, - 1140 + 1159
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_omega_I, input_orbital_angular_acceleration, - 1141 + 1160
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_LVLH_to_bodyframe_transformation_matrix, - 1142 + 1161
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_omega_LVLH_wrt_inertial_in_LVLH, input_evaluation_time); - 1143 + 1162 - 1144 + 1163
2/2
-
✓ Branch 0 taken 329664456 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 490987656 times.
+
✓ Branch 1 taken 81831276 times.
- 384608532 + 572818932 for (size_t ind = 0; - 1145 + 1164 - 384608532 + 572818932 ind < orbital_position_and_velocity_derivative_array.size(); ind++) { - 1146 + 1165 - 329664456 + 490987656 derivative_vec.at(ind) = - 1147 + 1166 - 329664456 + 490987656 orbital_position_and_velocity_derivative_array.at(ind); - 1148 + 1167 - 329664456 + 490987656 } - 1149 + 1168
2/2
-
✓ Branch 0 taken 384608532 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 572818932 times.
+
✓ Branch 1 taken 81831276 times.
- 439552608 + 654650208 for (size_t ind = 0; ind < angular_derivative_array.size(); ind++) { - 1150 + 1169 - 769217064 + 1145637864 derivative_vec.at(ind + - 1151 + 1170 - 769217064 + 1145637864 orbital_position_and_velocity_derivative_array.size()) = - 1152 + 1171 - 384608532 + 572818932 angular_derivative_array.at(ind); - 1153 + 1172 - 384608532 + 572818932 } - 1154 + 1173 - 1155 + 1174 - 54944076 + 81831276 return derivative_vec; - 1156 + 1175} - 1157 + 1176 - 1158 + 1177 - 8948066 + 12466977 std::array<double, 4> normalize_quaternion( - 1159 + 1178 std::array<double, 4> input_quaternion) { - 1160 + 1179 - 8948066 + 12466977 double length = 0; - 1161 + 1180
2/2
-
✓ Branch 0 taken 35792264 times.
-
✓ Branch 1 taken 8948066 times.
+
✓ Branch 0 taken 49867908 times.
+
✓ Branch 1 taken 12466977 times.
- 44740330 + 62334885 for (size_t ind = 0; ind < input_quaternion.size(); ind++) { - 1162 + 1181 - 35792264 + 49867908 length += (input_quaternion.at(ind) * input_quaternion.at(ind)); - 1163 + 1182 - 35792264 + 49867908 } - 1164 + 1183
2/2
-
✓ Branch 0 taken 35792264 times.
-
✓ Branch 1 taken 8948066 times.
+
✓ Branch 0 taken 49867908 times.
+
✓ Branch 1 taken 12466977 times.
- 44740330 + 62334885 for (size_t ind = 0; ind < input_quaternion.size(); ind++) { - 1165 + 1184 - 35792264 + 49867908 input_quaternion.at(ind) /= sqrt(length); - 1166 + 1185 - 35792264 + 49867908 } - 1167 + 1186 - 8948066 + 12466977 return input_quaternion; - 1168 + 1187 } - 1169 + 1188 - 1170 + 1189 - 8948009 + 12466918 std::array<double, 3> convert_quaternion_to_roll_yaw_pitch_angles( - 1171 + 1190 const std::array<double, 4> input_quaternion) { - 1172 + 1191 // Based on approach in - 1173 + 1192 // https://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/quat_2_euler_paper_ver2-1.pdf - 1174 + 1193 // Again, here I'm going off the pitch-yaw-roll sequence used in - 1175 + 1194 // https://ntrs.nasa.gov/api/citations/19770024112/downloads/19770024112.pdf - 1176 + 1195 // Where the angles which defined the orbiter attitude with respect to LVLH - 1177 + 1196 // are [A]_from_LVLH_to_BY = Rx(roll)*R_z(yaw)*R_y(pitch) - 1178 + 1197 - 1179 + 1198 - 17896018 + 24933836 Vector3d v3 = {0, 1, - 1180 + 1199 - 8948009 + 12466918 0}; // unit vector in direction of last rotation performed, - 1181 + 1200 // which in this sequence is the y unit vector - 1182 + 1201 - 17896018 + 24933836 Quaterniond eigen_quaternion(input_quaternion.at(0), input_quaternion.at(1), - 1183 + 1202 - 8948009 + 12466918 input_quaternion.at(2), input_quaternion.at(3)); - 1184 + 1203 - 8948009 + 12466918 eigen_quaternion.normalize(); // Just in case - 1185 + 1204 - 8948009 + 12466918 Matrix3d rotation_matrix = eigen_quaternion.toRotationMatrix(); - 1186 + 1205 - 8948009 + 12466918 Vector3d euler_angles = rotation_matrix.eulerAngles( - 1187 + 1206 0, 2, - 1188 + 1207 1); // Eigen uses intrinsic convention, so this is an intrinsic XZY - 1189 + 1208 // (denoted x-z'-y'' in the notation Wikipedia uses) or extrinsic YZX - 1190 + 1209 // sequence corresponding to R_x R_z R_y (e.g., see - 1191 + 1210 // https://arg.usask.ca/docs/skplatform/appendices/rotation_matrices.html) - 1192 + 1211 - 1193 + 1212 - 8948009 + 12466918 double roll = euler_angles(0); - 1194 + 1213 - 8948009 + 12466918 double yaw = euler_angles(1); - 1195 + 1214 - 8948009 + 12466918 double pitch = euler_angles(2); - 1196 + 1215 - 1197 + 1216 - 8948009 + 12466918 std::array<double, 3> output_angle_vec = {roll, yaw, pitch}; - 1198 + 1217 - 8948009 + 12466918 return output_angle_vec; - 1199 + 1218 } - 1200 + 1219 - 1201 + 1220 - 55 + 57 std::array<double, 3> convert_array_from_LVLH_to_bodyframe( - 1202 + 1221 const std::array<double, 3> input_LVLH_frame_array, const double input_roll, - 1203 + 1222 const double input_yaw, const double input_pitch) { - 1204 + 1223 Matrix3d transformation_matrix = - 1205 + 1224 - 55 + 57 rollyawpitch_bodyframe_to_LVLH_matrix(input_roll, input_pitch, input_yaw); - 1206 + 1225 - 110 + 114 Vector3d input_LVLH_frame_vector = {input_LVLH_frame_array.at(0), - 1207 + 1226 - 55 + 57 input_LVLH_frame_array.at(1), - 1208 + 1227 - 55 + 57 input_LVLH_frame_array.at(2)}; - 1209 + 1228 - 55 + 57 Vector3d bodyframe_vec = transformation_matrix * input_LVLH_frame_vector; - 1210 + 1229 - 110 + 114 std::array<double, 3> bodyframe_arr = {bodyframe_vec(0), bodyframe_vec(1), - 1211 + 1230 - 55 + 57 bodyframe_vec(2)}; - 1212 + 1231 - 55 + 57 return bodyframe_arr; - 1213 + 1232 } - 1214 + 1233 - 1215 + 1234 - - + 5 + Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, - 1216 + 1235 - + const double height) { - 1217 + 1236 5 - Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, const double height) { + double a = 6378137; // Equatorial radius [m] - 1218 + 1237 5 - double a = 6378137; // Equatorial radius [m] + double b = 6356752; // Polar radius [m] - 1219 + 1238 - 5 - double b = 6356752; // Polar radius [m] + + - 1220 + 1239 - + // Refs: - 1221 + 1240 - // Refs: https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#From_geodetic_to_ECEF_coordinates + // https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#From_geodetic_to_ECEF_coordinates - 1222 + 1241 // https://nssdc.gsfc.nasa.gov/planetary/factsheet/earthfact.html - 1223 + 1242 5 - double e = 1 - ((b * b)/(a * a)); + double e = 1 - ((b * b) / (a * a)); - 1224 + 1243 5 - double N = a / (sqrt(1 - ((e * e) / (1 + pow(cos(latitude)/sin(latitude),2)) ))); + double N = - 1225 + 1244 5 - double x = (N + height)*cos(latitude)*cos(longitude); + a / (sqrt(1 - ((e * e) / (1 + pow(cos(latitude) / sin(latitude), 2))))); - 1226 + 1245 5 - double y = (N + height)*cos(latitude)*sin(longitude); + double x = (N + height) * cos(latitude) * cos(longitude); - 1227 + 1246 5 - double z = ((1 - e * e)*N + height) * sin(latitude); + double y = (N + height) * cos(latitude) * sin(longitude); - 1228 + 1247 5 - Vector3d output_ECEF_array = {x,y,z}; + double z = ((1 - e * e) * N + height) * sin(latitude); - 1229 + 1248 + + + 5 + Vector3d output_ECEF_array = {x, y, z}; + + + 1249 5 return output_ECEF_array; - 1230 + 1250 } - 1231 + 1251 - 1232 + 1252 13480446 - Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, const double input_time) { + Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, - 1233 + 1253 - // Simple rotation-based conversion, not yet accounting for higher-fidelity effects like changes to Earth axes + const double input_time) { - 1234 + 1254 - // Ref: https://x-lumin.com/wp-content/uploads/2020/09/Coordinate_Transforms.pdf + // Simple rotation-based conversion, not yet accounting for higher-fidelity - 1235 + 1255 - // https://space.stackexchange.com/questions/43187/is-this-commonly-attributed-eci-earth-centered-inertial-to-ecef-earth-centere + // effects like changes to Earth axes Ref: - 1236 + 1256 - // https://space.stackexchange.com/questions/38807/transform-eci-to-ecef + // https://x-lumin.com/wp-content/uploads/2020/09/Coordinate_Transforms.pdf - 1237 + 1257 - 13480446 - double omega_Earth = 0.261799387799149 * (1.0/3600.0); // [radians / second] + + // https://space.stackexchange.com/questions/43187/is-this-commonly-attributed-eci-earth-centered-inertial-to-ecef-earth-centere - 1238 + 1258 + + + + // https://space.stackexchange.com/questions/38807/transform-eci-to-ecef + + + 1259 13480446 - double ERA_at_J200 = 280.46 * (M_PI/180); //radians + double omega_Earth = - 1239 + 1260 - // Going to be assuming, for simplicity, that satellites start orbiting at the J200 epoch + 0.261799387799149 * (1.0 / 3600.0); // [radians / second] - 1240 + 1261 13480446 - double theta_g = ERA_at_J200 + omega_Earth*input_time; + double ERA_at_J200 = 280.46 * (M_PI / 180); // radians - 1241 + 1262 - 13480446 - Matrix3d rotation_matrix = z_rot_matrix(theta_g); + + // Going to be assuming, for simplicity, that satellites start orbiting at the - 1242 + 1263 - 13480446 - Vector3d ECI_array = rotation_matrix*input_ECEF_position; + + // J200 epoch - 1243 + 1264 13480446 - return ECI_array; + double theta_g = ERA_at_J200 + omega_Earth * input_time; - 1244 + 1265 - - } + 13480446 + Matrix3d rotation_matrix = z_rot_matrix(theta_g); - 1245 + 1266 - - + 13480446 + Vector3d ECI_array = rotation_matrix * input_ECEF_position; - 1246 + 1267 - - + 13480446 + return ECI_array; - 1247 + 1268 - + } - 1248 + 1269 - 1249 + 1270 162 void sim_and_plot_gs_connectivity_distance_gnuplot( - 1250 + 1271 - PhasedArrayGroundStation input_ground_station, + PhasedArrayGroundStation input_ground_station, - 1251 + 1272 - std::vector<Satellite> input_satellite_vector, + std::vector<Satellite> input_satellite_vector, - 1252 + 1273 - const SimParameters& input_sim_parameters, + const SimParameters& input_sim_parameters, const std::string file_name) { - 1253 + 1274 - const std::string file_name) { + // Objective: given an input ground station and satellite vector, - 1254 + 1275 - + // plot contact distances between ground station and satellites over time - 1255 - - - - // Objective: given an input ground station and satellite vector, - - - 1256 - - - - // plot contact distances between ground station and satellites over time - - - 1257 + 1276 - 1258 + 1277
1/2 @@ -10390,56 +10511,56 @@

GCC Code Coverage Report

if (input_satellite_vector.size() < 1) { - 1259 + 1278 std::cout << "No input Satellite objects\n"; - 1260 + 1279 return; - 1261 + 1280 } - 1262 + 1281 - 1263 + 1282 // first, open "pipe" to gnuplot - 1264 + 1283 162 - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); - 1265 + 1284 // if it exists - 1266 + 1285
1/2 @@ -10453,112 +10574,140 @@

GCC Code Coverage Report

if (gnuplot_pipe) { - 1267 + 1286 162 - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, - 1268 + 1287 + + + + "set terminal png size 800,500 font ',14' linewidth 2\n"); + + + 1288 // formatting - 1269 + 1289 162 - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); - 1270 + 1290 162 fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); - 1271 + 1291 162 fprintf(gnuplot_pipe, "set ylabel 'Distance [m]'\n"); - 1272 + 1292 - 1273 + 1293 324 - fprintf(gnuplot_pipe, "set title 'Phased array ground station connectivity " + fprintf(gnuplot_pipe, - 1274 + 1294 + + + + "set title 'Phased array ground station connectivity " + + + 1295 + + + + "with %d beams'\n", + + + 1296 162 - "with %d beams'\n",input_ground_station.num_beams_); + input_ground_station.num_beams_); - 1275 + 1297 162 fprintf(gnuplot_pipe, "set key outside\n"); - 1276 + 1298 162 - int x_max_plot_window = std::floor(input_sim_parameters.total_sim_time*1.05); + int x_max_plot_window = - 1277 + 1299 162 - fprintf(gnuplot_pipe, "set xrange[0:%d]\n",x_max_plot_window); + std::floor(input_sim_parameters.total_sim_time * 1.05); - 1278 + 1300 + + + 162 + fprintf(gnuplot_pipe, "set xrange[0:%d]\n", x_max_plot_window); + + + 1301 // plotting - 1279 + 1302 - 1280 + 1303 // first satellite - 1281 + 1304 162 Satellite current_satellite = input_satellite_vector.at(0); - 1282 + 1305
2/2 @@ -10572,7 +10721,7 @@

GCC Code Coverage Report

if (input_satellite_vector.size() == 1) { - 1283 + 1306
2/2 @@ -10586,28 +10735,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1284 + 1307 27 fprintf(gnuplot_pipe, - 1285 + 1308 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \n", - 1286 + 1309 27 current_satellite.plotting_color_.c_str(), - 1287 + 1310
1/2 @@ -10621,28 +10770,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1288 + 1311 27 } else { - 1289 + 1312 27 fprintf(gnuplot_pipe, - 1290 + 1313 "plot '-' using 1:2 with lines lw 1 title '%s' \n", - 1291 + 1314
1/2 @@ -10656,42 +10805,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1292 + 1315 } - 1293 + 1316 - 1294 + 1317 54 } - 1295 + 1318 - 1296 + 1319 else { - 1297 + 1320
2/2 @@ -10705,28 +10854,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1298 + 1321 54 fprintf(gnuplot_pipe, - 1299 + 1322 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\\\n", - 1300 + 1323 54 current_satellite.plotting_color_.c_str(), - 1301 + 1324
1/2 @@ -10740,28 +10889,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1302 + 1325 54 } else { - 1303 + 1326 54 fprintf(gnuplot_pipe, - 1304 + 1327 "plot '-' using 1:2 with lines lw 1 title '%s'\\\n", - 1305 + 1328
1/2 @@ -10775,28 +10924,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1306 + 1329 } - 1307 + 1330 } - 1308 + 1331 - 1309 + 1332
2/2 @@ -10810,14 +10959,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 1; - 1310 + 1333 648 satellite_index < input_satellite_vector.size(); satellite_index++) { - 1311 + 1334
2/4 @@ -10833,7 +10982,7 @@

GCC Code Coverage Report

current_satellite = input_satellite_vector.at(satellite_index); - 1312 + 1335
2/2 @@ -10847,7 +10996,7 @@

GCC Code Coverage Report

if (satellite_index < input_satellite_vector.size() - 1) { - 1313 + 1336
2/2 @@ -10861,28 +11010,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1314 + 1337 162 fprintf(gnuplot_pipe, - 1315 + 1338 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \\\n", - 1316 + 1339 162 current_satellite.plotting_color_.c_str(), - 1317 + 1340
1/2 @@ -10896,28 +11045,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1318 + 1341 162 } else { - 1319 + 1342 216 fprintf(gnuplot_pipe, - 1320 + 1343 ",'-' using 1:2 with lines lw 1 title '%s' \\\n", - 1321 + 1344
1/2 @@ -10931,42 +11080,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1322 + 1345 } - 1323 + 1346 - 1324 + 1347 378 } - 1325 + 1348 - 1326 + 1349 else { - 1327 + 1350
2/2 @@ -10980,28 +11129,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1328 + 1351 54 fprintf(gnuplot_pipe, - 1329 + 1352 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\n", - 1330 + 1353 54 current_satellite.plotting_color_.c_str(), - 1331 + 1354
1/2 @@ -11015,21 +11164,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1332 + 1355 54 } else { - 1333 + 1356 54 fprintf(gnuplot_pipe, ",'-' using 1:2 with lines lw 1 title '%s'\n", - 1334 + 1357
1/2 @@ -11043,42 +11192,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1335 + 1358 } - 1336 + 1359 } - 1337 + 1360 486 } - 1338 + 1361 - 1339 + 1362 // now the orbit data, inline, one satellite at a time - 1340 + 1363
1/2 @@ -11092,7 +11241,7 @@

GCC Code Coverage Report

std::cout << "Running simulation...\n"; - 1341 + 1364
2/2 @@ -11106,14 +11255,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 0; - 1342 + 1365 810 satellite_index < input_satellite_vector.size(); satellite_index++) { - 1343 + 1366
2/4 @@ -11129,14 +11278,14 @@

GCC Code Coverage Report

Satellite current_satellite = input_satellite_vector.at(satellite_index); - 1344 + 1367 648 double current_satellite_time = - 1345 + 1368
1/2 @@ -11150,121 +11299,156 @@

GCC Code Coverage Report

current_satellite.get_instantaneous_time(); - 1346 + 1369 648 double previous_time = current_satellite_time - 1; - 1347 + 1370 + + + 648 + double ground_station_beam_angle = + + + 1371
- 2/4 + 1/2 +
+
✗ Branch 0 not taken.
+
✓ Branch 1 taken 648 times.
+
+
+ + 648 + input_ground_station.angle_to_satellite_from_normal( + + + 1372 + +
+ 1/2
✓ Branch 0 taken 648 times.
✗ Branch 1 not taken.
-
✗ Branch 2 not taken.
-
✓ Branch 3 taken 648 times.
648 - double ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + current_satellite); - 1348 + 1373 double initial_distance; - 1349 + 1374
- 1/2 + 2/4
✗ Branch 0 not taken.
✓ Branch 1 taken 648 times.
+
✗ Branch 2 not taken.
+
✓ Branch 3 taken 648 times.
- 648 - if (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) { + 1296 + if (ground_station_beam_angle > - 1350 + 1375 648 - fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); + input_ground_station.max_beam_angle_from_normal_) { - 1351 + 1376 648 - } + fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); - 1352 + 1377 - - else { + 648 + } else { - 1353 + 1378 ✗ - initial_distance = input_ground_station.distance_to_satellite(current_satellite); + initial_distance = - 1354 + 1379 ✗ - fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, initial_distance); + input_ground_station.distance_to_satellite(current_satellite); - 1355 + 1380 + + + ✗ + fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, + + + 1381 + + + ✗ + initial_distance); + + + 1382 } - 1356 + 1383 - + - 1357 + 1384 648 double evolved_distance = {0}; - 1358 + 1385 - 1359 + 1386 648 double timestep_to_use = input_sim_parameters.initial_timestep_guess; - 1360 + 1387
1/2 @@ -11278,7 +11462,7 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 1361 + 1388
2/2 @@ -11292,72 +11476,84 @@

GCC Code Coverage Report

while (current_satellite_time < input_sim_parameters.total_sim_time) { - 1362 + 1389 + + + 8747784 + std::pair<double, double> drag_elements = {input_sim_parameters.F_10, + + + 1390 4373892 - std::pair<double, double> drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + input_sim_parameters.A_p}; - 1363 + 1391 std::pair<double, int> new_timestep_and_error_code = - 1364 + 1392
- 2/4 + 1/2
✓ Branch 0 taken 4373892 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 4373892 times.
-
✗ Branch 3 not taken.
- 8747784 - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, + 4373892 + current_satellite.evolve_RK45( - 1365 + 1393 4373892 - input_sim_parameters.perturbation_bool, + input_sim_parameters.epsilon, timestep_to_use, - 1366 + 1394 4373892 - input_sim_parameters.drag_bool, drag_elements); + input_sim_parameters.perturbation_bool, - 1367 + 1395 + + + 4373892 + input_sim_parameters.drag_bool, drag_elements); + + + 1396 4373892 double new_timestep = new_timestep_and_error_code.first; - 1368 + 1397 4373892 int error_code = new_timestep_and_error_code.second; - 1369 + 1398 - 1370 + 1399
1/2 @@ -11371,56 +11567,70 @@

GCC Code Coverage Report

if (error_code != 0) { - 1371 + 1400 ✗ - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code - 1372 + 1401 + + + ✗ + << " detected, halting visualization\n"; + + + 1402 fprintf(gnuplot_pipe, "e\n"); - 1373 + 1403 fprintf(gnuplot_pipe, "exit \n"); - 1374 + 1404 pclose(gnuplot_pipe); - 1375 + 1405 return; - 1376 + 1406 } - 1377 + 1407 4373892 timestep_to_use = new_timestep; - 1378 + 1408 + + + 4373892 + evolved_distance = + + + 1409
2/4 @@ -11433,17 +11643,17 @@

GCC Code Coverage Report

4373892 - evolved_distance = input_ground_station.distance_to_satellite(current_satellite); + input_ground_station.distance_to_satellite(current_satellite); - 1379 + 1410 4373892 previous_time = current_satellite_time; - 1380 + 1411
1/2 @@ -11457,30 +11667,56 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 1381 + 1412 + + + 4373892 + ground_station_beam_angle = + + + 1413
- 2/4 + 1/2
✓ Branch 0 taken 4373892 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 4373892 times.
-
✗ Branch 3 not taken.
4373892 - ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + input_ground_station.angle_to_satellite_from_normal( - 1382 + 1414 + +
+ 1/2 +
+
✓ Branch 0 taken 4373892 times.
+
✗ Branch 1 not taken.
+
+
+ + 4373892 + current_satellite); + + + 1415 // Check number of existing connections to ground station at this point - 1383 + 1416 + + + 4373892 + int num_sats_at_this_time = + + + 1417
1/2 @@ -11491,47 +11727,75 @@

GCC Code Coverage Report

4373892 - int num_sats_at_this_time = input_ground_station.num_sats_connected_at_this_time(current_satellite_time); + input_ground_station.num_sats_connected_at_this_time( - 1384 + 1418 + + + 4373892 + current_satellite_time); + + + 1419 + +
+ 2/2 +
+
✓ Branch 0 taken 357471 times.
+
✓ Branch 1 taken 54882 times.
+
+
+ + 8747784 + if ((ground_station_beam_angle > + + + 1420
4/4
✓ Branch 0 taken 412353 times.
✓ Branch 1 taken 3961539 times.
-
✓ Branch 2 taken 357471 times.
-
✓ Branch 3 taken 54882 times.
+
✓ Branch 2 taken 412353 times.
+
✓ Branch 3 taken 3961539 times.
- 4373892 - if ( (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) || (num_sats_at_this_time == input_ground_station.num_beams_)) { + 8747784 + input_ground_station.max_beam_angle_from_normal_) || - 1385 + 1421 + + + 412353 + (num_sats_at_this_time == input_ground_station.num_beams_)) { + + + 1422 4016421 fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); - 1386 + 1423 4016421 - } + } else { - 1387 + 1424 - - else { + 357471 + evolved_distance = - 1388 + 1425
2/4 @@ -11544,17 +11808,24 @@

GCC Code Coverage Report

357471 - evolved_distance = input_ground_station.distance_to_satellite(current_satellite); + input_ground_station.distance_to_satellite(current_satellite); - 1389 + 1426 + + + 714942 + fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, + + + 1427 357471 - fprintf(gnuplot_pipe, "%.17g %.17g\n", current_satellite_time, evolved_distance); + evolved_distance); - 1390 + 1428
1/2 @@ -11565,31 +11836,38 @@

GCC Code Coverage Report

357471 - input_ground_station.update_linked_sats_map(satellite_index, current_satellite_time, previous_time); + input_ground_station.update_linked_sats_map( - 1391 + 1429 + + + 357471 + satellite_index, current_satellite_time, previous_time); + + + 1430 } - 1392 + 1431 } - 1393 + 1432 648 fprintf(gnuplot_pipe, "e\n"); - 1394 + 1433
1/2 @@ -11603,28 +11881,28 @@

GCC Code Coverage Report

} - 1395 + 1434 162 fprintf(gnuplot_pipe, "pause mouse keypress\n"); - 1396 + 1435 - 1397 + 1436 162 fprintf(gnuplot_pipe, "exit \n"); - 1398 + 1437
1/2 @@ -11638,7 +11916,7 @@

GCC Code Coverage Report

pclose(gnuplot_pipe); - 1399 + 1438
1/2 @@ -11652,14 +11930,14 @@

GCC Code Coverage Report

std::cout << "Done\n"; - 1400 + 1439 - 1401 + 1440
1/3 @@ -11674,112 +11952,98 @@

GCC Code Coverage Report

} else { - 1402 + 1441 std::cout << "gnuplot not found"; - 1403 + 1442 } - 1404 + 1443 - 1405 + 1444 162 return; - 1406 - - - - - - - 1407 + 1445 162 } - 1408 + 1446 - 1409 + 1447 162 - void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_station, - - - 1410 - - - - std::vector<Satellite> input_satellite_vector, + void sim_and_plot_gs_connectivity_gnuplot( - 1411 + 1448 - const SimParameters& input_sim_parameters, + PhasedArrayGroundStation input_ground_station, - 1412 + 1449 - const std::string file_name) { + std::vector<Satellite> input_satellite_vector, - 1413 + 1450 - + const SimParameters& input_sim_parameters, const std::string file_name) { - 1414 + 1451 // Objective: given an input ground station and satellite vector, - 1415 + 1452 // plot contact distances between ground station and satellites over time - 1416 + 1453 - 1417 + 1454
1/2 @@ -11793,56 +12057,56 @@

GCC Code Coverage Report

if (input_satellite_vector.size() < 1) { - 1418 + 1455 std::cout << "No input Satellite objects\n"; - 1419 + 1456 return; - 1420 + 1457 } - 1421 + 1458 - 1422 + 1459 // first, open "pipe" to gnuplot - 1423 + 1460 162 - FILE *gnuplot_pipe = popen("gnuplot", "w"); + FILE* gnuplot_pipe = popen("gnuplot", "w"); - 1424 + 1461 // if it exists - 1425 + 1462
1/2 @@ -11856,126 +12120,161 @@

GCC Code Coverage Report

if (gnuplot_pipe) { - 1426 + 1463 162 - fprintf(gnuplot_pipe, "set terminal png size 800,500 font ',14' linewidth 2\n"); + fprintf(gnuplot_pipe, - 1427 + 1464 + + + + "set terminal png size 800,500 font ',14' linewidth 2\n"); + + + 1465 // formatting - 1428 + 1466 162 - fprintf(gnuplot_pipe, "set output '../%s.png'\n",file_name.c_str()); + fprintf(gnuplot_pipe, "set output '../%s.png'\n", file_name.c_str()); - 1429 + 1467 162 fprintf(gnuplot_pipe, "set xlabel 'Time [s]'\n"); - 1430 + 1468 162 fprintf(gnuplot_pipe, "set ylabel 'Satellite Index'\n"); - 1431 + 1469 - 1432 + 1470 324 - fprintf(gnuplot_pipe, "set title 'Phased array ground station connectivity " + fprintf(gnuplot_pipe, - 1433 + 1471 + + + + "set title 'Phased array ground station connectivity " + + + 1472 + + + + "with %d beams'\n", + + + 1473 162 - "with %d beams'\n",input_ground_station.num_beams_); + input_ground_station.num_beams_); - 1434 + 1474 162 fprintf(gnuplot_pipe, "set key outside\n"); - 1435 + 1475 162 - int x_max_plot_window = std::floor(input_sim_parameters.total_sim_time*1.05); + int x_max_plot_window = - 1436 + 1476 162 - fprintf(gnuplot_pipe, "set xrange[0:%d]\n",x_max_plot_window); + std::floor(input_sim_parameters.total_sim_time * 1.05); - 1437 + 1477 162 - fprintf(gnuplot_pipe, "set yrange[-0.5:%lu]\n",input_satellite_vector.size()); + fprintf(gnuplot_pipe, "set xrange[0:%d]\n", x_max_plot_window); - 1438 + 1478 + + + 324 + fprintf(gnuplot_pipe, "set yrange[-0.5:%lu]\n", + + + 1479 + + + 162 + input_satellite_vector.size()); + + + 1480 - 1439 + 1481 // plotting - 1440 + 1482 - 1441 + 1483 // first satellite - 1442 + 1484 162 Satellite current_satellite = input_satellite_vector.at(0); - 1443 + 1485
2/2 @@ -11989,7 +12288,7 @@

GCC Code Coverage Report

if (input_satellite_vector.size() == 1) { - 1444 + 1486
2/2 @@ -12003,28 +12302,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1445 + 1487 27 fprintf(gnuplot_pipe, - 1446 + 1488 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \n", - 1447 + 1489 27 current_satellite.plotting_color_.c_str(), - 1448 + 1490
1/2 @@ -12038,28 +12337,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1449 + 1491 27 } else { - 1450 + 1492 27 fprintf(gnuplot_pipe, - 1451 + 1493 "plot '-' using 1:2 with lines lw 1 title '%s' \n", - 1452 + 1494
1/2 @@ -12073,42 +12372,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1453 + 1495 } - 1454 + 1496 - 1455 + 1497 54 } - 1456 + 1498 - 1457 + 1499 else { - 1458 + 1500
2/2 @@ -12122,28 +12421,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1459 + 1501 54 fprintf(gnuplot_pipe, - 1460 + 1502 "plot '-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\\\n", - 1461 + 1503 54 current_satellite.plotting_color_.c_str(), - 1462 + 1504
1/2 @@ -12157,28 +12456,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1463 + 1505 54 } else { - 1464 + 1506 54 fprintf(gnuplot_pipe, - 1465 + 1507 "plot '-' using 1:2 with lines lw 1 title '%s'\\\n", - 1466 + 1508
1/2 @@ -12192,28 +12491,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1467 + 1509 } - 1468 + 1510 } - 1469 + 1511 - 1470 + 1512
2/2 @@ -12227,14 +12526,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 1; - 1471 + 1513 648 - satellite_index < input_satellite_vector.size(); satellite_index++) { + satellite_index < input_satellite_vector.size(); satellite_index++) { - 1472 + 1514
2/4 @@ -12250,7 +12549,7 @@

GCC Code Coverage Report

current_satellite = input_satellite_vector.at(satellite_index); - 1473 + 1515
2/2 @@ -12264,7 +12563,7 @@

GCC Code Coverage Report

if (satellite_index < input_satellite_vector.size() - 1) { - 1474 + 1516
2/2 @@ -12278,28 +12577,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1475 + 1517 162 fprintf(gnuplot_pipe, - 1476 + 1518 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s' \\\n", - 1477 + 1519 162 current_satellite.plotting_color_.c_str(), - 1478 + 1520
1/2 @@ -12313,28 +12612,28 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1479 + 1521 162 } else { - 1480 + 1522 216 fprintf(gnuplot_pipe, - 1481 + 1523 ",'-' using 1:2 with lines lw 1 title '%s' \\\n", - 1482 + 1524
1/2 @@ -12348,42 +12647,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1483 + 1525 } - 1484 + 1526 - 1485 + 1527 378 } - 1486 + 1528 - 1487 + 1529 else { - 1488 + 1530
2/2 @@ -12397,28 +12696,28 @@

GCC Code Coverage Report

if (current_satellite.plotting_color_.size() > 0) { - 1489 + 1531 54 fprintf(gnuplot_pipe, - 1490 + 1532 ",'-' using 1:2 with lines lw 1 lc rgb '%s' title '%s'\n", - 1491 + 1533 54 current_satellite.plotting_color_.c_str(), - 1492 + 1534
1/2 @@ -12432,21 +12731,21 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1493 + 1535 54 } else { - 1494 + 1536 54 fprintf(gnuplot_pipe, ",'-' using 1:2 with lines lw 1 title '%s'\n", - 1495 + 1537
1/2 @@ -12460,42 +12759,42 @@

GCC Code Coverage Report

current_satellite.get_name().c_str()); - 1496 + 1538 } - 1497 + 1539 } - 1498 + 1540 486 } - 1499 + 1541 - 1500 + 1542 // now the orbit data, inline, one satellite at a time - 1501 + 1543
1/2 @@ -12509,7 +12808,7 @@

GCC Code Coverage Report

std::cout << "Running simulation...\n"; - 1502 + 1544
2/2 @@ -12523,14 +12822,14 @@

GCC Code Coverage Report

for (size_t satellite_index = 0; - 1503 + 1545 810 - satellite_index < input_satellite_vector.size(); satellite_index++) { + satellite_index < input_satellite_vector.size(); satellite_index++) { - 1504 + 1546
2/4 @@ -12546,14 +12845,14 @@

GCC Code Coverage Report

Satellite current_satellite = input_satellite_vector.at(satellite_index); - 1505 + 1547 648 double current_satellite_time = - 1506 + 1548
1/2 @@ -12567,100 +12866,128 @@

GCC Code Coverage Report

current_satellite.get_instantaneous_time(); - 1507 + 1549 648 double previous_time = current_satellite_time - 1; - 1508 + 1550 + + + 648 + double ground_station_beam_angle = + + + 1551
- 2/4 + 1/2 +
+
✗ Branch 0 not taken.
+
✓ Branch 1 taken 648 times.
+
+
+ + 648 + input_ground_station.angle_to_satellite_from_normal( + + + 1552 + +
+ 1/2
✓ Branch 0 taken 648 times.
✗ Branch 1 not taken.
-
✗ Branch 2 not taken.
-
✓ Branch 3 taken 648 times.
648 - double ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + current_satellite); - 1509 + 1553 - 1510 + 1554
- 1/2 + 2/4
✓ Branch 0 taken 648 times.
✗ Branch 1 not taken.
+
✓ Branch 2 taken 648 times.
+
✗ Branch 3 not taken.
- 648 - if (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) { + 1296 + if (ground_station_beam_angle > - 1511 + 1555 648 - fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); + input_ground_station.max_beam_angle_from_normal_) { - 1512 + 1556 648 - } + fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); - 1513 + 1557 - - else { + 648 + } else { - 1514 + 1558 ✗ - fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, satellite_index); + fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, - 1515 + 1559 + + + ✗ + satellite_index); + + + 1560 } - 1516 + 1561 - + - 1517 + 1562 648 double timestep_to_use = input_sim_parameters.initial_timestep_guess; - 1518 + 1563
1/2 @@ -12674,7 +13001,7 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 1519 + 1564
2/2 @@ -12688,72 +13015,84 @@

GCC Code Coverage Report

while (current_satellite_time < input_sim_parameters.total_sim_time) { - 1520 + 1565 + + + 8747784 + std::pair<double, double> drag_elements = {input_sim_parameters.F_10, + + + 1566 4373892 - std::pair<double, double> drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; + input_sim_parameters.A_p}; - 1521 + 1567 std::pair<double, int> new_timestep_and_error_code = - 1522 + 1568
- 2/4 + 1/2
✓ Branch 0 taken 4373892 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 4373892 times.
-
✗ Branch 3 not taken.
- 8747784 - current_satellite.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, + 4373892 + current_satellite.evolve_RK45( - 1523 + 1569 4373892 - input_sim_parameters.perturbation_bool, + input_sim_parameters.epsilon, timestep_to_use, - 1524 + 1570 4373892 - input_sim_parameters.drag_bool, drag_elements); + input_sim_parameters.perturbation_bool, - 1525 + 1571 + + + 4373892 + input_sim_parameters.drag_bool, drag_elements); + + + 1572 4373892 double new_timestep = new_timestep_and_error_code.first; - 1526 + 1573 4373892 int error_code = new_timestep_and_error_code.second; - 1527 + 1574 - 1528 + 1575
1/2 @@ -12767,63 +13106,70 @@

GCC Code Coverage Report

if (error_code != 0) { - 1529 + 1576 ✗ - std::cout << "Error code " << error_code << " detected, halting visualization\n"; + std::cout << "Error code " << error_code - 1530 + 1577 + + + ✗ + << " detected, halting visualization\n"; + + + 1578 fprintf(gnuplot_pipe, "e\n"); - 1531 + 1579 fprintf(gnuplot_pipe, "exit \n"); - 1532 + 1580 pclose(gnuplot_pipe); - 1533 + 1581 return; - 1534 + 1582 } - 1535 + 1583 4373892 timestep_to_use = new_timestep; - 1536 + 1584 4373892 previous_time = current_satellite_time; - 1537 + 1585
1/2 @@ -12837,30 +13183,56 @@

GCC Code Coverage Report

current_satellite_time = current_satellite.get_instantaneous_time(); - 1538 + 1586 + + + 4373892 + ground_station_beam_angle = + + + 1587
- 2/4 + 1/2
✓ Branch 0 taken 4373892 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 4373892 times.
-
✗ Branch 3 not taken.
4373892 - ground_station_beam_angle = input_ground_station.angle_to_satellite_from_normal(current_satellite); + input_ground_station.angle_to_satellite_from_normal( - 1539 + 1588 + +
+ 1/2 +
+
✓ Branch 0 taken 4373892 times.
+
✗ Branch 1 not taken.
+
+
+ + 4373892 + current_satellite); + + + 1589 // Check number of existing connections to ground station at this point - 1540 + 1590 + + + 4373892 + int num_sats_at_this_time = + + + 1591
1/2 @@ -12871,54 +13243,82 @@

GCC Code Coverage Report

4373892 - int num_sats_at_this_time = input_ground_station.num_sats_connected_at_this_time(current_satellite_time); + input_ground_station.num_sats_connected_at_this_time( - 1541 + 1592 + + + 4373892 + current_satellite_time); + + + 1593 + +
+ 2/2 +
+
✓ Branch 0 taken 357471 times.
+
✓ Branch 1 taken 54882 times.
+
+
+ + 8747784 + if ((ground_station_beam_angle > + + + 1594
4/4
✓ Branch 0 taken 412353 times.
✓ Branch 1 taken 3961539 times.
-
✓ Branch 2 taken 357471 times.
-
✓ Branch 3 taken 54882 times.
+
✓ Branch 2 taken 412353 times.
+
✓ Branch 3 taken 3961539 times.
- 4373892 - if ( (ground_station_beam_angle > input_ground_station.max_beam_angle_from_normal_) || (num_sats_at_this_time == input_ground_station.num_beams_)) { + 8747784 + input_ground_station.max_beam_angle_from_normal_) || - 1542 + 1595 + + + 412353 + (num_sats_at_this_time == input_ground_station.num_beams_)) { + + + 1596 4016421 fprintf(gnuplot_pipe, "%.17g NaN\n", current_satellite_time); - 1543 + 1597 4016421 - } + } else { - 1544 + 1598 - - else { + 714942 + fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, - 1545 + 1599 357471 - fprintf(gnuplot_pipe, "%.17g %lu\n", current_satellite_time, satellite_index); + satellite_index); - 1546 + 1600
1/2 @@ -12929,31 +13329,38 @@

GCC Code Coverage Report

357471 - input_ground_station.update_linked_sats_map(satellite_index, current_satellite_time, previous_time); + input_ground_station.update_linked_sats_map( - 1547 + 1601 + + + 357471 + satellite_index, current_satellite_time, previous_time); + + + 1602 } - 1548 + 1603 } - 1549 + 1604 648 fprintf(gnuplot_pipe, "e\n"); - 1550 + 1605
1/2 @@ -12967,77 +13374,77 @@

GCC Code Coverage Report

} - 1551 + 1606 // for (auto key_val_pair : input_ground_station.linked_sats_map_) { - 1552 + 1607 // std::cout << "==========================================\n"; - 1553 + 1608 // std::cout << "Satellite index " << key_val_pair.first << "\n"; - 1554 + 1609 // for (std::pair<double,double> range : key_val_pair.second) { - 1555 + 1610 // std::cout << "{" << range.first << "," << range.second << "}\n"; - 1556 + 1611 // } - 1557 + 1612 // } - 1558 + 1613 162 fprintf(gnuplot_pipe, "pause mouse keypress\n"); - 1559 + 1614 - 1560 + 1615 162 fprintf(gnuplot_pipe, "exit \n"); - 1561 + 1616
1/2 @@ -13051,7 +13458,7 @@

GCC Code Coverage Report

pclose(gnuplot_pipe); - 1562 + 1617
1/2 @@ -13065,14 +13472,14 @@

GCC Code Coverage Report

std::cout << "Done\n"; - 1563 + 1618 - 1564 + 1619
1/3 @@ -13087,98 +13494,105 @@

GCC Code Coverage Report

} else { - 1565 + 1620 std::cout << "gnuplot not found"; - 1566 + 1621 } - 1567 + 1622 - 1568 + 1623 162 return; - 1569 - - - - - - - 1570 + 1624 162 } - 1571 + 1625 - 1572 + 1626 + + + 2 + int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, + + + 1627 - + const double final_orbit_semimajor_axis_km, - 1573 + 1628 - 2 - int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double final_orbit_semimajor_axis_km, + + const double input_thrust_magnitude, - 1574 + 1629 - const double input_thrust_magnitude, const double transfer_initiation_time) { + const double transfer_initiation_time) { - 1575 + 1630 // Only transfers between circular orbits are supported at this time - 1576 + 1631 // Ref: https://prussing.ae.illinois.edu/AE402/low.thrust.pdf - 1577 + 1632 2 int error_code = 0; - 1578 + 1633 + + + 2 + double initial_eccentricity = + + + 1634
1/2 @@ -13189,10 +13603,10 @@

GCC Code Coverage Report

2 - double initial_eccentricity = input_satellite_object.get_orbital_parameter("Eccentricity"); + input_satellite_object.get_orbital_parameter("Eccentricity"); - 1579 + 1635
2/2 @@ -13206,35 +13620,35 @@

GCC Code Coverage Report

if (initial_eccentricity != 0) { - 1580 + 1636 1 std::cout << "Satellite's initial orbit was not circular\n"; - 1581 + 1637 1 error_code = 1; - 1582 + 1638 1 } - 1583 + 1639 2 double satellite_mass = input_satellite_object.get_mass(); - 1584 + 1640
1/2 @@ -13248,42 +13662,49 @@

GCC Code Coverage Report

if (satellite_mass <= 0) { - 1585 + 1641 std::cout << "Error: satellite mass was <= 0\n"; - 1586 + 1642 error_code = 2; - 1587 + 1643 } - 1588 + 1644 2 - double thrust_acceleration = input_thrust_magnitude/satellite_mass; + double thrust_acceleration = input_thrust_magnitude / satellite_mass; - 1589 + 1645 2 - double semimajor_axis_final = 1000 * final_orbit_semimajor_axis_km; // m + double semimajor_axis_final = 1000 * final_orbit_semimajor_axis_km; // m - 1590 + 1646 + + + 2 + double semimajor_axis_initial = + + + 1647
1/2 @@ -13294,66 +13715,66 @@

GCC Code Coverage Report

2 - double semimajor_axis_initial = input_satellite_object.get_orbital_parameter("Semimajor Axis"); + input_satellite_object.get_orbital_parameter("Semimajor Axis"); - 1591 + 1648 2 - const double mu_Earth = G*mass_Earth; + const double mu_Earth = G * mass_Earth; - 1592 + 1649 2 - double comp1 =sqrt(mu_Earth/semimajor_axis_initial); + double comp1 = sqrt(mu_Earth / semimajor_axis_initial); - 1593 + 1650 2 - double comp2 = sqrt(mu_Earth/semimajor_axis_final); + double comp2 = sqrt(mu_Earth / semimajor_axis_final); - 1594 + 1651 2 - double time_to_burn = (comp1-comp2)/thrust_acceleration; + double time_to_burn = (comp1 - comp2) / thrust_acceleration; - 1595 + 1652 - + - 1596 + 1653 - // Thrust is purely co-linear with velocity vector, so in the +- x direction of the LVLH frame + // Thrust is purely co-linear with velocity vector, so in the +- x direction - 1597 + 1654 - // (along +x if raising orbit, -x if lowering orbit) + // of the LVLH frame (along +x if raising orbit, -x if lowering orbit) - 1598 + 1655 - std::array<double,3> LVLH_thrust_direction; + std::array<double, 3> LVLH_thrust_direction; - 1599 + 1656
1/2 @@ -13367,77 +13788,84 @@

GCC Code Coverage Report

if (semimajor_axis_initial < semimajor_axis_final) { - 1600 + 1657 2 - LVLH_thrust_direction = {1,0,0}; + LVLH_thrust_direction = {1, 0, 0}; - 1601 + 1658 +
+ 0/2 +
+
✗ Branch 0 not taken.
+
✗ Branch 1 not taken.
+
+
- 2 - } + 2 + } else if (semimajor_axis_initial > semimajor_axis_final) { - 1602 + 1659 ✗ - else if (semimajor_axis_initial > semimajor_axis_final) { + LVLH_thrust_direction = {-1, 0, 0}; - 1603 + 1660 ✗ - LVLH_thrust_direction = {-1,0,0}; + time_to_burn = - 1604 + 1661 ✗ - time_to_burn = (-1)*time_to_burn; // Since this would have otherwise been negative + (-1) * time_to_burn; // Since this would have otherwise been negative - 1605 + 1662 ✗ - } + } else { - 1606 + 1663 - - else { + ✗ + std::cout << "Error: initial and final semimajor axes were equal.\n"; - 1607 + 1664 ✗ - std::cout << "Error: initial and final semimajor axes were equal.\n"; + error_code = 3; // Arbitrarily choose a burn direction in this scenario, - 1608 + 1665 - ✗ - error_code = 3; // Arbitrarily choose a burn direction in this scenario, since it shouldn't matter + + // since it shouldn't matter - 1609 + 1666 } - 1610 + 1667
2/2 @@ -13451,350 +13879,49 @@

GCC Code Coverage Report

if (error_code == 0) { - 1611 + 1668 2 - input_satellite_object.add_LVLH_thrust_profile(LVLH_thrust_direction, input_thrust_magnitude, + input_satellite_object.add_LVLH_thrust_profile( - 1612 + 1669 1 - transfer_initiation_time, transfer_initiation_time + time_to_burn); + LVLH_thrust_direction, input_thrust_magnitude, transfer_initiation_time, - 1613 + 1670 1 - } - - - 1614 - - - 2 - return error_code; - - - 1615 - - - ✗ - } - - - 1616 - - - - - - - 1617 - - - ✗ - double calibrate_mean_val(Satellite satellite_object, const SimParameters& input_sim_parameters, const std::string input_parameter_name) { - - - 1618 - - - - // Objective: help calibrate simulations in context of inherent oscillations of parameters - - - 1619 - - - - // Here, the mean value of oscillations will be assumed to be constant (oscillations don't drift up or down over time) - - - 1620 - - - - - - - 1621 - - - - // Let the simulation run without external applied forces, return mean value of parameter - - - 1622 - - - - // Not passing in satellite object by ref so that its internal clock doesn't get altered from its initial value before the actual - - - 1623 - - - - // simulations start - - - 1624 - - - - - - - 1625 - - - ✗ - double val = - - - 1626 - - - ✗ - satellite_object.get_orbital_parameter(input_parameter_name); - - - 1627 - - - ✗ - double mean_val = val; - - - 1628 - - - ✗ - size_t num_datapoints = 1; + transfer_initiation_time + time_to_burn); - 1629 + 1671 - ✗ - double current_satellite_time = - - - 1630 - - - ✗ - satellite_object.get_instantaneous_time(); - - - 1631 - - - - - - - 1632 - - - ✗ - double evolved_val = {0}; - - - 1633 - - - - - - - 1634 - - - ✗ - double timestep_to_use = input_sim_parameters.initial_timestep_guess; - - - 1635 - - - ✗ - current_satellite_time = satellite_object.get_instantaneous_time(); - - - 1636 - - - ✗ - while (current_satellite_time < input_sim_parameters.total_sim_time) { - - - 1637 - - - ✗ - std::pair<double, double> drag_elements = {input_sim_parameters.F_10, input_sim_parameters.A_p}; - - - 1638 - - - - std::pair<double, int> new_timestep_and_error_code = - - - 1639 - - - ✗ - satellite_object.evolve_RK45(input_sim_parameters.epsilon, timestep_to_use, - - - 1640 - - - ✗ - input_sim_parameters.perturbation_bool, - - - 1641 - - - ✗ - input_sim_parameters.drag_bool, drag_elements); - - - 1642 - - - ✗ - double new_timestep = new_timestep_and_error_code.first; - - - 1643 - - - ✗ - int error_code = new_timestep_and_error_code.second; - - - 1644 - - - - - - - 1645 - - - ✗ - if (error_code != 0) { - - - 1646 - - - ✗ - std::cout << "Error code " << error_code << " detected, halting simulation and returning 0\n"; - - - 1647 - - - ✗ - return 0.0; - - - 1648 - - - - } - - - 1649 - - - ✗ - timestep_to_use = new_timestep; - - - 1650 - - - ✗ - evolved_val = - - - 1651 - - - ✗ - satellite_object.get_orbital_parameter(input_parameter_name); - - - 1652 - - - ✗ - mean_val += evolved_val; - - - 1653 - - - ✗ - num_datapoints+=1; - - - 1654 - - - - - - - 1655 - - - ✗ - current_satellite_time = satellite_object.get_instantaneous_time(); - - - 1656 - - - - } - - - 1657 - - - ✗ - mean_val /= num_datapoints; + 1 + } - 1658 + 1672 - ✗ - return mean_val; + 2 + return error_code; - 1659 + 1673} - 1660 + 1674 diff --git a/tests/test_coverage_detailed.utils.h.0924fa377d356c0f9a6a386ccdf5fa6d.html b/tests/test_coverage_detailed.utils.h.0924fa377d356c0f9a6a386ccdf5fa6d.html index 4e910b8..f9fa459 100644 --- a/tests/test_coverage_detailed.utils.h.0924fa377d356c0f9a6a386ccdf5fa6d.html +++ b/tests/test_coverage_detailed.utils.h.0924fa377d356c0f9a6a386ccdf5fa6d.html @@ -26,7 +26,7 @@

GCC Code Coverage Report

Date: - 2025-05-06 17:04:10 + 2025-05-07 02:51:48 @@ -70,9 +70,9 @@

GCC Code Coverage Report

Call count Block coverage - SimParameters::SimParameters(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 33)called 10 times100.0% - SimParameters::~SimParameters() (line 20)called 10 times100.0% - std::__1::pair<std::__1::array<double, 13>, std::__1::pair<double, double>> RK45_step<13>(std::__1::array<double, 13>, double, std::__1::function<std::__1::array<double, 13> (std::__1::array<double, 13>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool)>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, bool, double, double, double) (line 346)called 9157346 times87.0% + SimParameters::SimParameters(std::__1::basic_string<char, std::__1::char_traits<char>, std::__1::allocator<char>>) (line 32)called 10 times100.0% + SimParameters::~SimParameters() (line 19)called 10 times100.0% + std::__1::pair<std::__1::array<double, 13>, std::__1::pair<double, double>> RK45_step<13>(std::__1::array<double, 13>, double, std::__1::function<std::__1::array<double, 13> (std::__1::array<double, 13>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, double, bool, bool)>, Eigen::Matrix<double, 3, 3, 0, 3, 3>, std::__1::vector<BodyframeTorqueProfile, std::__1::allocator<BodyframeTorqueProfile>>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, Eigen::Matrix<double, 3, 3, 0, 3, 3>, Eigen::Matrix<double, 3, 1, 0, 3, 1>, double, std::__1::vector<ThrustProfileLVLH, std::__1::allocator<ThrustProfileLVLH>>, double, double, double, double, double, double, bool, double, double, double) (line 348)called 13638546 times87.0%
@@ -147,14 +147,14 @@

GCC Code Coverage Report

- #include "Satellite.h" + #include "PhasedArrayGroundStation.h" 10 - #include "PhasedArrayGroundStation.h" + #include "Satellite.h" 11 @@ -217,108 +217,101 @@

GCC Code Coverage Report

- - - - 20 - - - struct SimParameters { - 21 + 20 5 double initial_timestep_guess = 1; - 22 + 21 5 double total_sim_time = 10; - 23 + 22 5 double epsilon = pow(10, -8); - 24 + 23 5 bool perturbation_bool = true; - 25 + 24 5 bool drag_bool = false; - 26 + 25 5 double x_increment = 0; - 27 + 26 5 double y_increment = 0; - 28 + 27 5 double z_increment = 0; - 29 + 28 5 double F_10 = 0; // Solar radio ten centimeter flux - 30 + 29 5 double A_p = 0; // Geomagnetic A_p index - 31 + 30 5 std::string terminal_name_3D = "qt"; - 32 + 31 - 33 + 32 10 SimParameters(const std::string parameter_json_file_name) { - 34 + 33
1/2 @@ -332,7 +325,7 @@

GCC Code Coverage Report

std::ifstream input_filestream(parameter_json_file_name); - 35 + 34
1/2 @@ -346,14 +339,14 @@

GCC Code Coverage Report

json input_data = json::parse(input_filestream); - 36 + 35 - 37 + 36
3/6 @@ -371,7 +364,7 @@

GCC Code Coverage Report

if (input_data.find("Initial timestep guess") != input_data.end()) { - 38 + 37
2/4 @@ -387,14 +380,14 @@

GCC Code Coverage Report

initial_timestep_guess = input_data.at("Initial timestep guess"); - 39 + 38 5 } - 40 + 39
3/6 @@ -412,7 +405,7 @@

GCC Code Coverage Report

if (input_data.find("Simulation duration") != input_data.end()) { - 41 + 40
2/4 @@ -428,14 +421,14 @@

GCC Code Coverage Report

total_sim_time = input_data.at("Simulation duration"); - 42 + 41 5 } - 43 + 42
3/6 @@ -453,7 +446,7 @@

GCC Code Coverage Report

if (input_data.find("epsilon") != input_data.end()) { - 44 + 43
2/4 @@ -469,14 +462,14 @@

GCC Code Coverage Report

epsilon = input_data.at("epsilon"); - 45 + 44 5 } - 46 + 45
3/6 @@ -494,7 +487,7 @@

GCC Code Coverage Report

if (input_data.find("Perturbation") != input_data.end()) { - 47 + 46
2/4 @@ -510,14 +503,14 @@

GCC Code Coverage Report

perturbation_bool = input_data.at("Perturbation"); - 48 + 47 5 } - 49 + 48
3/6 @@ -535,7 +528,7 @@

GCC Code Coverage Report

if (input_data.find("Drag") != input_data.end()) { - 50 + 49
2/4 @@ -551,14 +544,14 @@

GCC Code Coverage Report

drag_bool = input_data.at("Drag"); - 51 + 50 5 } - 52 + 51
3/6 @@ -576,21 +569,21 @@

GCC Code Coverage Report

if (input_data.find("X increment") != input_data.end()) { - 53 + 52 x_increment = input_data.at("X increment"); - 54 + 53 } - 55 + 54
3/6 @@ -608,21 +601,21 @@

GCC Code Coverage Report

if (input_data.find("Y increment") != input_data.end()) { - 56 + 55 y_increment = input_data.at("Y increment"); - 57 + 56 } - 58 + 57
3/6 @@ -640,21 +633,21 @@

GCC Code Coverage Report

if (input_data.find("Z increment") != input_data.end()) { - 59 + 58 z_increment = input_data.at("Z increment"); - 60 + 59 } - 61 + 60
3/6 @@ -672,214 +665,221 @@

GCC Code Coverage Report

if (input_data.find("3D plotting terminal") != input_data.end()) { - 62 + 61 terminal_name_3D = input_data.at("3D plotting terminal"); - 63 + 62 } - 64 + 63 10 } - 65 + 64 }; - 66 + 65 - 67 + 66 std::array<double, 3> calculate_orbital_acceleration( - 68 + 67 const std::array<double, 3> input_r_vec, const double input_spacecraft_mass, - 69 + 68 const std::vector<std::array<double, 3>> input_vec_of_force_vectors_in_ECI = - 70 + 69 {}); - 71 + 70 std::array<double, 3> calculate_orbital_acceleration( - 72 + 71 const std::array<double, 3> input_r_vec, const double input_spacecraft_mass, - 73 + 72 const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, - 74 + 73 const double input_evaluation_time, - 75 + 74 const std::array<double, 3> input_velocity_vec, - 76 + 75 const double input_inclination, const double input_arg_of_periapsis, - 77 + 76 const double input_true_anomaly, const double input_F_10, - 78 + 77 const double input_A_p, const double input_A_s, - 79 + 78 const double input_satellite_mass, const bool perturbation, - 80 + 79 const bool atmospheric_drag); - 81 + 80 - 82 + 81 std::array<double, 6> RK4_deriv_function_orbit_position_and_velocity( - 83 + 82 const std::array<double, 6> input_position_and_velocity, - 84 + 83 const double input_spacecraft_mass, - 85 + 84 const std::vector<std::array<double, 3>> input_vec_of_force_vectors_in_ECI = - 86 + 85 {}); - 87 + 86 - 88 + 87 // template <int T> - 89 + 88 // std::array<double, T> RK4_step( - 90 + 89 // const std::array<double, T> y_n, const double input_step_size, + + 90 + + + + // std::function<std::array<double, T>(const std::array<double, T> + 91 - // std::function<std::array<double, T>(const std::array<double, T> input_y_vec, + // input_y_vec, 92 @@ -893,441 +893,441 @@

GCC Code Coverage Report

- // const std::vector<std::array<double, 3>> + // const std::vector<std::array<double, 94 - // input_vec_of_force_vectors_in_ECI)> + // 3>> 95 - // input_derivative_function, + // input_vec_of_force_vectors_in_ECI)> 96 - // const double input_spacecraft_mass, + // input_derivative_function, 97 - // const std::vector<std::array<double, 3>> + // const double input_spacecraft_mass, 98 - // input_vec_of_force_vectors_in_ECI_at_t = {}, + // const std::vector<std::array<double, 3>> 99 - // const std::vector<std::array<double, 3>> + // input_vec_of_force_vectors_in_ECI_at_t = {}, 100 - // input_vec_of_force_vectors_in_ECI_at_t_and_halfstep = {}, + // const std::vector<std::array<double, 3>> 101 - // const std::vector<std::array<double, 3>> + // input_vec_of_force_vectors_in_ECI_at_t_and_halfstep = {}, 102 - // input_vec_of_force_vectors_in_ECI_at_t_and_step = {}) { + // const std::vector<std::array<double, 3>> 103 - // // ref: + // input_vec_of_force_vectors_in_ECI_at_t_and_step = {}) { 104 - // // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method + // // ref: 105 - // std::array<double, T> y_nplus1 = y_n; + // // 106 - + // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method 107 - // // first, k=1; + // std::array<double, T> y_nplus1 = y_n; 108 - // // going to be assuming derivative function does not have explicit time + 109 - // // dependence + // // first, k=1; 110 - // std::array<double, T> k_1 = input_derivative_function( + // // going to be assuming derivative function does not have explicit time 111 - // y_n, input_spacecraft_mass, input_vec_of_force_vectors_in_ECI_at_t); + // // dependence 112 - + // std::array<double, T> k_1 = input_derivative_function( 113 - // // now k_2 + // y_n, input_spacecraft_mass, input_vec_of_force_vectors_in_ECI_at_t); 114 - // std::array<double, T> y_vec_for_k_2 = y_n; + 115 - // for (size_t ind = 0; ind < T; ind++) { + // // now k_2 116 - // y_vec_for_k_2.at(ind) += ((input_step_size / 2) * k_1.at(ind)); + // std::array<double, T> y_vec_for_k_2 = y_n; 117 - // } + // for (size_t ind = 0; ind < T; ind++) { 118 - + // y_vec_for_k_2.at(ind) += ((input_step_size / 2) * k_1.at(ind)); 119 - // std::array<double, T> k_2 = input_derivative_function( + // } 120 - // y_vec_for_k_2, input_spacecraft_mass, + 121 - // input_vec_of_force_vectors_in_ECI_at_t_and_halfstep); + // std::array<double, T> k_2 = input_derivative_function( 122 - // // now k_3 + // y_vec_for_k_2, input_spacecraft_mass, 123 - // std::array<double, T> y_vec_for_k_3 = y_n; + // input_vec_of_force_vectors_in_ECI_at_t_and_halfstep); 124 - // for (size_t ind = 0; ind < T; ind++) { + // // now k_3 125 - // y_vec_for_k_3.at(ind) += ((input_step_size / 2) * k_2.at(ind)); + // std::array<double, T> y_vec_for_k_3 = y_n; 126 - // } + // for (size_t ind = 0; ind < T; ind++) { 127 - + // y_vec_for_k_3.at(ind) += ((input_step_size / 2) * k_2.at(ind)); 128 - // std::array<double, T> k_3 = input_derivative_function( + // } 129 - // y_vec_for_k_3, input_spacecraft_mass, + 130 - // input_vec_of_force_vectors_in_ECI_at_t_and_halfstep); + // std::array<double, T> k_3 = input_derivative_function( 131 - + // y_vec_for_k_3, input_spacecraft_mass, 132 - // // now k_4 + // input_vec_of_force_vectors_in_ECI_at_t_and_halfstep); 133 - // std::array<double, T> y_vec_for_k_4 = y_n; + 134 - // for (size_t ind = 0; ind < T; ind++) { + // // now k_4 135 - // y_vec_for_k_4.at(ind) += (input_step_size * k_3.at(ind)); + // std::array<double, T> y_vec_for_k_4 = y_n; 136 - // } + // for (size_t ind = 0; ind < T; ind++) { 137 - + // y_vec_for_k_4.at(ind) += (input_step_size * k_3.at(ind)); 138 - // std::array<double, T> k_4 = input_derivative_function( + // } 139 - // y_vec_for_k_4, input_spacecraft_mass, + 140 - // input_vec_of_force_vectors_in_ECI_at_t_and_step); + // std::array<double, T> k_4 = input_derivative_function( 141 - + // y_vec_for_k_4, input_spacecraft_mass, 142 - // for (size_t ind = 0; ind < T; ind++) { + // input_vec_of_force_vectors_in_ECI_at_t_and_step); 143 - // y_nplus1.at(ind) += + 144 - // ((input_step_size / 6) * + // for (size_t ind = 0; ind < T; ind++) { 145 - // (k_1.at(ind) + 2 * k_2.at(ind) + 2 * k_3.at(ind) + k_4.at(ind))); + // y_nplus1.at(ind) += 146 - // } + // ((input_step_size / 6) * 147 - + // (k_1.at(ind) + 2 * k_2.at(ind) + 2 * k_3.at(ind) + k_4.at(ind))); 148 - // return y_nplus1; + // } 149 - // } + 150 - + // return y_nplus1; 151 - void sim_and_draw_orbit_gnuplot( + // } 152 - std::vector<Satellite> input_satellite_vector, + 153 - const SimParameters& input_sim_parameters, + void sim_and_draw_orbit_gnuplot(std::vector<Satellite> input_satellite_vector, 154 - const std::string output_file_name = "output" + const SimParameters& input_sim_parameters, 155 - ); + const std::string output_file_name = "output"); 156 @@ -1425,217 +1425,217 @@

GCC Code Coverage Report

- // Version for satellite orbital motion time evolution + // std::cout << "In RK45_step, received perturbation bool: " << perturbation 170 - // Implementing RK4(5) method for its adaptive step size + // << "\n"; 171 - // Refs:https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method + // Version for satellite orbital motion time evolution 172 - // , + // Implementing RK4(5) method for its adaptive step size 173 - // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method + // Refs:https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method 174 - std::array<double, 6> nodes = {0.0, 1.0 / 4, 3.0 / 8, 12.0 / 13, + // , 175 - 1.0, 1.0 / 2}; // c coefficients + // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method 176 - std::array<double, 6> CH_vec = {16.0 / 135, 0.0, 6656.0 / 12825, + std::array<double, 6> nodes = {0.0, 1.0 / 4, 3.0 / 8, 12.0 / 13, 177 - 28561.0 / 56430, -9.0 / 50, 2.0 / 55}; + 1.0, 1.0 / 2}; // c coefficients 178 - std::array<double, 6> CT_vec = {-1.0 / 360, 0.0, 128.0 / 4275, + std::array<double, 6> CH_vec = {16.0 / 135, 0.0, 6656.0 / 12825, 179 - 2197.0 / 75240, -1.0 / 50, -2.0 / 55}; + 28561.0 / 56430, -9.0 / 50, 2.0 / 55}; 180 - int s = 6; + std::array<double, 6> CT_vec = {-1.0 / 360, 0.0, 128.0 / 4275, 181 - + 2197.0 / 75240, -1.0 / 50, -2.0 / 55}; 182 - MatrixXd RK_matrix = MatrixXd::Zero(s, s); + int s = 6; 183 - RK_matrix(1, 0) = 1.0 / 4; + 184 - RK_matrix(2, 0) = 3.0 / 32; + MatrixXd RK_matrix = MatrixXd::Zero(s, s); 185 - RK_matrix(2, 1) = 9.0 / 32; + RK_matrix(1, 0) = 1.0 / 4; 186 - RK_matrix(3, 0) = 1932.0 / 2197; + RK_matrix(2, 0) = 3.0 / 32; 187 - RK_matrix(3, 1) = -7200.0 / 2197; + RK_matrix(2, 1) = 9.0 / 32; 188 - RK_matrix(3, 2) = 7296.0 / 2197; + RK_matrix(3, 0) = 1932.0 / 2197; 189 - RK_matrix(4, 0) = 439.0 / 216; + RK_matrix(3, 1) = -7200.0 / 2197; 190 - RK_matrix(4, 1) = -8.0; + RK_matrix(3, 2) = 7296.0 / 2197; 191 - RK_matrix(4, 2) = 3680.0 / 513; + RK_matrix(4, 0) = 439.0 / 216; 192 - RK_matrix(4, 3) = -845.0 / 4104; + RK_matrix(4, 1) = -8.0; 193 - RK_matrix(5, 0) = -8.0 / 27; + RK_matrix(4, 2) = 3680.0 / 513; 194 - RK_matrix(5, 1) = 2.0; + RK_matrix(4, 3) = -845.0 / 4104; 195 - RK_matrix(5, 2) = -3544.0 / 2565; + RK_matrix(5, 0) = -8.0 / 27; 196 - RK_matrix(5, 3) = 1859.0 / 4104; + RK_matrix(5, 1) = 2.0; 197 - RK_matrix(5, 4) = -11.0 / 40; + RK_matrix(5, 2) = -3544.0 / 2565; 198 - + RK_matrix(5, 3) = 1859.0 / 4104; 199 - std::vector<std::array<double, T>> k_vec_vec = {}; + RK_matrix(5, 4) = -11.0 / 40; 200 @@ -1649,175 +1649,175 @@

GCC Code Coverage Report

- // Need to populate k_vec (compute vector k_i for i=0...s-1) + std::vector<std::array<double, T>> k_vec_vec = {}; 202 - for (size_t k_ind = 0; k_ind < s; k_ind++) { + 203 - double evaluation_time = input_t_n + (nodes.at(k_ind) * input_step_size); + // Need to populate k_vec (compute vector k_i for i=0...s-1) 204 - std::array<double, T> y_n_evaluated_value = y_n; + for (size_t k_ind = 0; k_ind < s; k_ind++) { 205 - std::array<double, T> k_vec_at_this_s; + double evaluation_time = input_t_n + (nodes.at(k_ind) * input_step_size); 206 - for (size_t s_ind = 0; s_ind < k_ind; s_ind++) { + std::array<double, T> y_n_evaluated_value = y_n; 207 - for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { + std::array<double, T> k_vec_at_this_s; 208 - y_n_evaluated_value.at(y_val_ind) += RK_matrix(k_ind, s_ind) * + for (size_t s_ind = 0; s_ind < k_ind; s_ind++) { 209 - k_vec_vec.at(s_ind).at(y_val_ind); + for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { 210 - } + y_n_evaluated_value.at(y_val_ind) += 211 - } + RK_matrix(k_ind, s_ind) * k_vec_vec.at(s_ind).at(y_val_ind); 212 - std::array<double, 6> derivative_function_output = + } 213 - input_derivative_function(y_n_evaluated_value, input_spacecraft_mass, + } 214 - input_list_of_thrust_profiles_LVLH, + std::array<double, 6> derivative_function_output = 215 - evaluation_time, input_inclination, + input_derivative_function(y_n_evaluated_value, input_spacecraft_mass, 216 - input_arg_of_periapsis, input_true_anomaly, + input_list_of_thrust_profiles_LVLH, 217 - perturbation); + evaluation_time, input_inclination, 218 - for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { + input_arg_of_periapsis, input_true_anomaly, 219 - k_vec_at_this_s.at(y_val_ind) = + perturbation); 220 - input_step_size * derivative_function_output.at(y_val_ind); + for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { 221 - } + k_vec_at_this_s.at(y_val_ind) = 222 - k_vec_vec.push_back(k_vec_at_this_s); + input_step_size * derivative_function_output.at(y_val_ind); 223 - } + } 224 - + k_vec_vec.push_back(k_vec_at_this_s); 225 - std::array<double, T> y_nplusone = y_n; + } 226 @@ -1831,175 +1831,175 @@

GCC Code Coverage Report

- for (size_t s_ind = 0; s_ind < s; s_ind++) { + std::array<double, T> y_nplusone = y_n; 228 - for (size_t y_ind = 0; y_ind < y_n.size(); y_ind++) { + 229 - double tmp = CH_vec.at(s_ind) * k_vec_vec.at(s_ind).at(y_ind); + for (size_t s_ind = 0; s_ind < s; s_ind++) { 230 - y_nplusone.at(y_ind) += tmp; + for (size_t y_ind = 0; y_ind < y_n.size(); y_ind++) { 231 - } + double tmp = CH_vec.at(s_ind) * k_vec_vec.at(s_ind).at(y_ind); 232 - } + y_nplusone.at(y_ind) += tmp; 233 - + } 234 - std::array<double, T> TE_vec; + } 235 - for (size_t s_ind = 0; s_ind < s; s_ind++) { + 236 - for (size_t y_ind = 0; y_ind < std::size(TE_vec); y_ind++) { + std::array<double, T> TE_vec; 237 - TE_vec.at(y_ind) += CT_vec.at(s_ind) * k_vec_vec.at(s_ind).at(y_ind); + for (size_t s_ind = 0; s_ind < s; s_ind++) { 238 - } + for (size_t y_ind = 0; y_ind < std::size(TE_vec); y_ind++) { 239 - } + TE_vec.at(y_ind) += CT_vec.at(s_ind) * k_vec_vec.at(s_ind).at(y_ind); 240 - + } 241 - for (size_t y_ind = 0; y_ind < std::size(TE_vec); y_ind++) { + } 242 - TE_vec.at(y_ind) = abs(TE_vec.at(y_ind)); + 243 - } + for (size_t y_ind = 0; y_ind < std::size(TE_vec); y_ind++) { 244 - // I'm going to use the max TE found across the whole position+velocity vec as + TE_vec.at(y_ind) = abs(TE_vec.at(y_ind)); 245 - // the TE in the calculation of the next stepsize + } 246 - double max_TE = TE_vec.at( + // I'm going to use the max TE found across the whole position+velocity vec as 247 - std::distance(std::begin(TE_vec), + // the TE in the calculation of the next stepsize 248 - std::max_element(std::begin(TE_vec), std::end(TE_vec)))); + double max_TE = TE_vec.at( 249 - double epsilon_ratio = input_epsilon / max_TE; + std::distance(std::begin(TE_vec), 250 - + std::max_element(std::begin(TE_vec), std::end(TE_vec)))); 251 - double h_new = 0.9 * input_step_size * std::pow(epsilon_ratio, 1.0 / 5); + double epsilon_ratio = input_epsilon / max_TE; 252 @@ -2013,392 +2013,392 @@

GCC Code Coverage Report

- if (max_TE <= input_epsilon) { + double h_new = 0.9 * input_step_size * std::pow(epsilon_ratio, 1.0 / 5); 254 - std::pair<double, double> output_timestep_pair; + 255 - output_timestep_pair.first = + if (max_TE <= input_epsilon) { 256 - input_step_size; // First timestep size in this pair is the one + std::pair<double, double> output_timestep_pair; 257 - // successfully used in this calculation + output_timestep_pair.first = 258 - output_timestep_pair.second = + input_step_size; // First timestep size in this pair is the one 259 - h_new; // Second timestep size in this pair is the one to be used in + // successfully used in this calculation 260 - // the next step + output_timestep_pair.second = 261 - std::pair<std::array<double, T>, std::pair<double, double>> output_pair; + h_new; // Second timestep size in this pair is the one to be used in 262 - output_pair.first = y_nplusone; + // the next step 263 - output_pair.second = output_timestep_pair; + std::pair<std::array<double, T>, std::pair<double, double>> output_pair; 264 - return output_pair; + output_pair.first = y_nplusone; 265 - } else { + output_pair.second = output_timestep_pair; 266 - return RK45_step<T>( + return output_pair; 267 - y_n, h_new, input_derivative_function, input_spacecraft_mass, + } else { 268 - input_list_of_thrust_profiles_LVLH, input_t_n, input_epsilon, + return RK45_step<T>( 269 - input_inclination, input_arg_of_periapsis, input_true_anomaly, + y_n, h_new, input_derivative_function, input_spacecraft_mass, 270 - perturbation); + input_list_of_thrust_profiles_LVLH, input_t_n, input_epsilon, 271 - } + input_inclination, input_arg_of_periapsis, input_true_anomaly, 272 - } + perturbation); 273 - + } 274 - std::array<double, 3> convert_LVLH_to_ECI_manual( + } 275 - const std::array<double, 3> input_LVLH_vec, + 276 - const std::array<double, 3> input_position_vec, + std::array<double, 3> convert_LVLH_to_ECI_manual( 277 - const std::array<double, 3> input_velocity_vec); + const std::array<double, 3> input_LVLH_vec, 278 - + const std::array<double, 3> input_position_vec, 279 - std::array<double, 6> RK45_deriv_function_orbit_position_and_velocity( + const std::array<double, 3> input_velocity_vec); 280 - const std::array<double, 6> input_position_and_velocity, + 281 - const double input_spacecraft_mass, + std::array<double, 6> RK45_deriv_function_orbit_position_and_velocity( 282 - const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, + const std::array<double, 6> input_position_and_velocity, 283 - const double input_evaluation_time, const double input_inclination, + const double input_spacecraft_mass, 284 - const double input_arg_of_periapsis, const double input_true_anomaly, + const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, 285 - const double input_F_10, const double input_A_p, const double input_A_s, + const double input_evaluation_time, const double input_inclination, 286 - const double input_satellite_mass, const bool perturbation, + const double input_arg_of_periapsis, const double input_true_anomaly, 287 - const bool atmospheric_drag); + const double input_F_10, const double input_A_p, const double input_A_s, 288 - + const double input_satellite_mass, const bool perturbation, 289 - std::array<double, 3> convert_cylindrical_to_cartesian( + const bool atmospheric_drag); 290 - const double input_r_comp, const double input_theta_comp, + 291 - const double input_z_comp, const double input_theta); + std::array<double, 3> convert_cylindrical_to_cartesian( 292 - void sim_and_plot_orbital_elem_gnuplot( + const double input_r_comp, const double input_theta_comp, 293 - std::vector<Satellite> input_satellite_vector, + const double input_z_comp, const double input_theta); 294 - const SimParameters& input_sim_parameters, + void sim_and_plot_orbital_elem_gnuplot( 295 - const std::string input_orbital_element_name, + std::vector<Satellite> input_satellite_vector, 296 - const std::string file_name = "output"); + const SimParameters& input_sim_parameters, 297 - void sim_and_plot_attitude_evolution_gnuplot( + const std::string input_orbital_element_name, 298 - std::vector<Satellite> input_satellite_vector, + const std::string file_name = "output"); 299 - const SimParameters& input_sim_parameters, + void sim_and_plot_attitude_evolution_gnuplot( 300 - const std::string input_plotted_val_name, + std::vector<Satellite> input_satellite_vector, 301 - const std::string file_name = "output"); + const SimParameters& input_sim_parameters, 302 - + const std::string input_plotted_val_name, 303 - Matrix3d rollyawpitch_bodyframe_to_LVLH( + const std::string file_name = "output"); 304 - const std::array<double, 3> input_bodyframe_vec, const double input_roll, + 305 - const double input_pitch, const double input_yaw); + Matrix3d rollyawpitch_bodyframe_to_LVLH( 306 - std::array<double, 4> rollyawpitch_angles_to_quaternion( + const std::array<double, 3> input_bodyframe_vec, const double input_roll, 307 - const double input_roll, const double input_pitch, const double input_yaw); + const double input_pitch, const double input_yaw); 308 - std::array<double, 4> rollpitchyaw_angles_to_quaternion( + std::array<double, 4> rollyawpitch_angles_to_quaternion( 309 @@ -2412,1866 +2412,1901 @@

GCC Code Coverage Report

- + std::array<double, 4> rollpitchyaw_angles_to_quaternion( 311 - Matrix3d LVLH_to_body_transformation_matrix_from_quaternion( + const double input_roll, const double input_pitch, const double input_yaw); 312 - const std::array<double, 4> input_bodyframe_quaternion_relative_to_LVLH); + 313 - Vector4d quaternion_multiplication(const Vector4d quaternion_1, + Matrix3d LVLH_to_body_transformation_matrix_from_quaternion( 314 - const Vector4d quaternion_2); + const std::array<double, 4> input_bodyframe_quaternion_relative_to_LVLH); 315 - Vector4d quaternion_kinematics_equation( + Vector4d quaternion_multiplication(const Vector4d quaternion_1, 316 - const Vector4d quaternion_of_bodyframe_relative_to_ref_frame, + const Vector4d quaternion_2); 317 - const Vector3d angular_velocity_vec_wrt_ref_frame_in_body_frame); + Vector4d quaternion_kinematics_equation( 318 - std::array<double, 7> RK45_satellite_body_angular_deriv_function( + const Vector4d quaternion_of_bodyframe_relative_to_ref_frame, 319 - const std::array<double, 7> combined_bodyframe_angular_array, + const Vector3d angular_velocity_vec_wrt_ref_frame_in_body_frame); 320 - const Matrix3d J_matrix, + std::array<double, 7> RK45_satellite_body_angular_deriv_function( 321 - const std::vector<BodyframeTorqueProfile> + const std::array<double, 7> combined_bodyframe_angular_array, 322 - input_bodyframe_torque_profile_list, + const Matrix3d J_matrix, 323 - const Vector3d input_omega_I, + const std::vector<BodyframeTorqueProfile> 324 - const double input_orbital_angular_acceleration, + input_bodyframe_torque_profile_list, 325 - const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, + const Vector3d input_omega_I, 326 - const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, + const double input_orbital_angular_acceleration, 327 - const double input_evaluation_time); + const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, 328 - std::array<double, 13> + const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, 329 - RK45_combined_orbit_position_velocity_attitude_deriv_function( + const double input_evaluation_time); 330 - const std::array<double, 13> + std::array<double, 13> 331 - combined_position_velocity_bodyframe_angular_array, + RK45_combined_orbit_position_velocity_attitude_deriv_function( 332 - const Matrix3d J_matrix, + const std::array<double, 13> 333 - const std::vector<BodyframeTorqueProfile> + combined_position_velocity_bodyframe_angular_array, 334 - input_bodyframe_torque_profile_list, + const Matrix3d J_matrix, 335 - const Vector3d input_omega_I, double input_orbital_angular_acceleration, + const std::vector<BodyframeTorqueProfile> 336 - const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, + input_bodyframe_torque_profile_list, 337 - const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, + const Vector3d input_omega_I, double input_orbital_angular_acceleration, 338 - const double input_spacecraft_mass, + const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, 339 - const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, + const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, 340 - const double input_evaluation_time, const double input_inclination, + const double input_spacecraft_mass, 341 - const double input_arg_of_periapsis, const double input_true_anomaly, + const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, 342 - const double input_F_10, const double input_A_p, const double input_A_s, + const double input_evaluation_time, const double input_inclination, 343 - const bool perturbation, const bool atmospheric_drag); + const double input_arg_of_periapsis, const double input_true_anomaly, 344 - + const double input_F_10, const double input_A_p, const double input_A_s, 345 - template <int T> + const bool perturbation, const bool atmospheric_drag); 346 - 9157346 - std::pair<std::array<double, T>, std::pair<double, double>> RK45_step( + + 347 - const std::array<double, T> y_n, const double input_step_size, + template <int T> 348 + 13638546 + std::pair<std::array<double, T>, std::pair<double, double>> RK45_step( + + + 349 + + + + const std::array<double, T> y_n, const double input_step_size, + + + 350 + + std::function<std::array<double, T>( - 349 + 351 const std::array<double, T>, const Matrix3d, - 350 + 352 const std::vector<BodyframeTorqueProfile>, const Vector3d, const double, - 351 + 353 const Matrix3d, const Vector3d, const double, - 352 + 354 const std::vector<ThrustProfileLVLH>, const double, const double, - 353 + 355 const double, const double, const double, const double, const double, - 354 + 356 const bool, const bool)> - 355 + 357 input_combined_derivative_function, - 356 + 358 const Matrix3d J_matrix, - 357 + 359 const std::vector<BodyframeTorqueProfile> - 358 + 360 input_bodyframe_torque_profile_list, - 359 + 361 const Vector3d input_omega_I, double input_orbital_angular_acceleration, - 360 + 362 const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, - 361 + 363 const Vector3d input_omega_LVLH_wrt_inertial_in_LVLH, - 362 + 364 const double input_spacecraft_mass, - 363 + 365 const std::vector<ThrustProfileLVLH> input_list_of_thrust_profiles_LVLH, - 364 + 366 const double input_inclination, const double input_arg_of_periapsis, - 365 + 367 const double input_true_anomaly, const double input_F_10, - 366 + 368 const double input_A_p, const double input_A_s, const bool perturbation, - 367 + 369 const double atmospheric_drag, const double input_t_n, - 368 + 370 const double input_epsilon) { - 369 + 371 // Version for combined satellite orbital motion and attitude time evolution - 370 + 372 // Implementing RK4(5) method for its adaptive step size - 371 + 373 // Refs:https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method - 372 + 374 // , - 373 + 375 // https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta_methods#The_Runge%E2%80%93Kutta_method - 374 + 376 - 375 + 377 - 9157346 + 13638546 std::array<double, 6> nodes = {0.0, 1.0 / 4, 3.0 / 8, 12.0 / 13, - 376 + 378 1.0, 1.0 / 2}; // c coefficients - 377 + 379 - 9157346 + 13638546 std::array<double, 6> CH_vec = {16.0 / 135, 0.0, 6656.0 / 12825, - 378 + 380 28561.0 / 56430, -9.0 / 50, 2.0 / 55}; - 379 + 381 - 9157346 + 13638546 std::array<double, 6> CT_vec = {-1.0 / 360, 0.0, 128.0 / 4275, - 380 + 382 2197.0 / 75240, -1.0 / 50, -2.0 / 55}; - 381 + 383 - 9157346 + 13638546 int s = 6; - 382 + 384 - 383 + 385 - 9157346 + 13638546 MatrixXd RK_matrix = MatrixXd::Zero(s, s); - 384 + 386
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(1, 0) = 1.0 / 4; - 385 + 387
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(2, 0) = 3.0 / 32; - 386 + 388
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(2, 1) = 9.0 / 32; - 387 + 389
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(3, 0) = 1932.0 / 2197; - 388 + 390
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(3, 1) = -7200.0 / 2197; - 389 + 391
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(3, 2) = 7296.0 / 2197; - 390 + 392
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(4, 0) = 439.0 / 216; - 391 + 393
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(4, 1) = -8.0; - 392 + 394
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(4, 2) = 3680.0 / 513; - 393 + 395
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(4, 3) = -845.0 / 4104; - 394 + 396
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(5, 0) = -8.0 / 27; - 395 + 397
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(5, 1) = 2.0; - 396 + 398
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(5, 2) = -3544.0 / 2565; - 397 + 399
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(5, 3) = 1859.0 / 4104; - 398 + 400
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 RK_matrix(5, 4) = -11.0 / 40; - 399 + 401 - 400 + 402 - 9157346 + 13638546 std::vector<std::array<double, T>> k_vec_vec = {}; - 401 + 403 - 402 + 404 // Need to populate k_vec (compute vector k_i for i=0...s-1) - 403 + 405
2/2
-
✓ Branch 0 taken 54944076 times.
-
✓ Branch 1 taken 9157346 times.
+
✓ Branch 0 taken 81831276 times.
+
✓ Branch 1 taken 13638546 times.
- 64101422 + 95469822 for (size_t k_ind = 0; k_ind < s; k_ind++) { - 404 + 406
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 double evaluation_time = input_t_n + (nodes.at(k_ind) * input_step_size); - 405 + 407 - 54944076 + 81831276 std::array<double, T> y_n_evaluated_value = y_n; - 406 + 408 std::array<double, T> k_vec_at_this_s; - 407 + 409
2/2
-
✓ Branch 0 taken 54944076 times.
-
✓ Branch 1 taken 137360190 times.
+
✓ Branch 0 taken 81831276 times.
+
✓ Branch 1 taken 204578190 times.
- 192304266 + 286409466 for (size_t s_ind = 0; s_ind < k_ind; s_ind++) { - 408 + 410
2/2
-
✓ Branch 0 taken 1785682470 times.
-
✓ Branch 1 taken 137360190 times.
+
✓ Branch 0 taken 2659516470 times.
+
✓ Branch 1 taken 204578190 times.
- 1923042660 + 2864094660 for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { - 409 + 411
1/2
-
✓ Branch 0 taken 1785682470 times.
+
✓ Branch 0 taken 2659516470 times.
✗ Branch 1 not taken.
- 3571364940 + 5319032940 y_n_evaluated_value.at(y_val_ind) += input_step_size * - 410 + 412
1/2
-
✓ Branch 0 taken 1785682470 times.
+
✓ Branch 0 taken 2659516470 times.
✗ Branch 1 not taken.
- 1785682470 + 2659516470 RK_matrix(k_ind, s_ind) * - 411 + 413
2/4
-
✓ Branch 0 taken 1785682470 times.
+
✓ Branch 0 taken 2659516470 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 1785682470 times.
+
✓ Branch 2 taken 2659516470 times.
✗ Branch 3 not taken.
- 1785682470 + 2659516470 k_vec_vec.at(s_ind).at(y_val_ind); - 412 + 414 - 1785682470 + 2659516470 } - 413 + 415 - 137360190 + 204578190 } - 414 + 416 std::array<double, T> derivative_function_output = - 415 + 417
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_combined_derivative_function( - 416 + 418
2/4
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 54944076 times.
+
✓ Branch 2 taken 81831276 times.
✗ Branch 3 not taken.
- 54944076 + 81831276 y_n_evaluated_value, J_matrix, input_bodyframe_torque_profile_list, - 417 + 419
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_omega_I, input_orbital_angular_acceleration, - 418 + 420
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_LVLH_to_bodyframe_transformation_matrix, - 419 + 421
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_omega_LVLH_wrt_inertial_in_LVLH, input_spacecraft_mass, - 420 + 422
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 input_list_of_thrust_profiles_LVLH, evaluation_time, - 421 + 423 - 54944076 + 81831276 input_inclination, input_arg_of_periapsis, input_true_anomaly, - 422 + 424 - 54944076 + 81831276 input_F_10, input_A_p, input_A_s, perturbation, atmospheric_drag); - 423 + 425
2/2
-
✓ Branch 0 taken 54944076 times.
-
✓ Branch 1 taken 714272988 times.
+
✓ Branch 0 taken 81831276 times.
+
✓ Branch 1 taken 1063806588 times.
- 769217064 + 1145637864 for (size_t y_val_ind = 0; y_val_ind < y_n.size(); y_val_ind++) { - 424 + 426
1/2
-
✓ Branch 0 taken 714272988 times.
+
✓ Branch 0 taken 1063806588 times.
✗ Branch 1 not taken.
- 714272988 + 1063806588 k_vec_at_this_s.at(y_val_ind) = - 425 + 427
1/2
-
✓ Branch 0 taken 714272988 times.
+
✓ Branch 0 taken 1063806588 times.
✗ Branch 1 not taken.
- 714272988 + 1063806588 input_step_size * derivative_function_output.at(y_val_ind); - 426 + 428 - 714272988 + 1063806588 } - 427 + 429 - 428 + 430
1/2
-
✓ Branch 0 taken 54944076 times.
+
✓ Branch 0 taken 81831276 times.
✗ Branch 1 not taken.
- 54944076 + 81831276 k_vec_vec.push_back(k_vec_at_this_s); - 429 + 431 - 54944076 + 81831276 } - 430 + 432 - 431 + 433 - 9157346 + 13638546 std::array<double, T> y_nplusone = y_n; - 432 + 434 - 433 + 435
2/2
-
✓ Branch 0 taken 9157346 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 13638546 times.
+
✓ Branch 1 taken 81831276 times.
- 64101422 + 95469822 for (size_t s_ind = 0; s_ind < s; s_ind++) { - 434 + 436
2/2
-
✓ Branch 0 taken 714272988 times.
-
✓ Branch 1 taken 54944076 times.
+
✓ Branch 0 taken 1063806588 times.
+
✓ Branch 1 taken 81831276 times.
- 769217064 + 1145637864 for (size_t y_ind = 0; y_ind < y_n.size(); y_ind++) { - 435 + 437
3/6
-
✓ Branch 0 taken 714272988 times.
+
✓ Branch 0 taken 1063806588 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 714272988 times.
+
✓ Branch 2 taken 1063806588 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 714272988 times.
+
✓ Branch 4 taken 1063806588 times.
✗ Branch 5 not taken.
- 714272988 + 1063806588 double tmp = CH_vec.at(s_ind) * k_vec_vec.at(s_ind).at(y_ind); - 436 + 438
1/2
-
✓ Branch 0 taken 714272988 times.
+
✓ Branch 0 taken 1063806588 times.
✗ Branch 1 not taken.
- 714272988 + 1063806588 y_nplusone.at(y_ind) += tmp; - 437 + 439 - 714272988 + 1063806588 } - 438 + 440 - 54944076 + 81831276 } - 439 + 441 - 440 + 442 - 9157346 + 13638546 std::array<double, T> TE_vec = {0}; - 441 + 443
2/2
-
✓ Branch 0 taken 9157346 times.
-
✓ Branch 1 taken 119045498 times.
+
✓ Branch 0 taken 13638546 times.
+
✓ Branch 1 taken 177301098 times.
- 128202844 + 190939644 for (size_t y_ind = 0; y_ind < y_n.size(); y_ind++) { - 442 + 444
2/2
-
✓ Branch 0 taken 714272988 times.
-
✓ Branch 1 taken 119045498 times.
+
✓ Branch 0 taken 1063806588 times.
+
✓ Branch 1 taken 177301098 times.
- 833318486 + 1241107686 for (size_t s_ind = 0; s_ind < s; s_ind++) { - 443 + 445
4/8
-
✓ Branch 0 taken 714272988 times.
+
✓ Branch 0 taken 1063806588 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 714272988 times.
+
✓ Branch 2 taken 1063806588 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 714272988 times.
+
✓ Branch 4 taken 1063806588 times.
✗ Branch 5 not taken.
-
✓ Branch 6 taken 714272988 times.
+
✓ Branch 6 taken 1063806588 times.
✗ Branch 7 not taken.
- 714272988 + 1063806588 TE_vec.at(y_ind) += CT_vec.at(s_ind) * k_vec_vec.at(s_ind).at(y_ind); - 444 + 446 - 714272988 + 1063806588 } - 445 + 447 - 119045498 + 177301098 } - 446 + 448 - 447 + 449
2/2
-
✓ Branch 0 taken 9157346 times.
-
✓ Branch 1 taken 119045498 times.
+
✓ Branch 0 taken 13638546 times.
+
✓ Branch 1 taken 177301098 times.
- 128202844 + 190939644 for (size_t ind = 0; ind < TE_vec.size(); ind++) { - 448 + 450
2/4
-
✓ Branch 0 taken 119045498 times.
+
✓ Branch 0 taken 177301098 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 119045498 times.
+
✓ Branch 2 taken 177301098 times.
✗ Branch 3 not taken.
- 119045498 + 177301098 TE_vec.at(ind) = abs(TE_vec.at(ind)); - 449 + 451 - 119045498 + 177301098 } - 450 + 452 - 451 + 453 // I'm going to use the max TE found across the whole position+velocity vec as - 452 + 454 // the TE in the calculation of the next stepsize - 453 + 455
1/2
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
- 9157346 + 13638546 double max_TE = TE_vec.at( - 454 + 456
2/4
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 9157346 times.
+
✓ Branch 2 taken 13638546 times.
✗ Branch 3 not taken.
- 18314692 + 27277092 std::distance(std::begin(TE_vec), - 455 + 457
3/6
-
✓ Branch 0 taken 9157346 times.
+
✓ Branch 0 taken 13638546 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 9157346 times.
+
✓ Branch 2 taken 13638546 times.
✗ Branch 3 not taken.
-
✓ Branch 4 taken 9157346 times.
+
✓ Branch 4 taken 13638546 times.
✗ Branch 5 not taken.
- 9157346 + 13638546 std::max_element(std::begin(TE_vec), std::end(TE_vec)))); - 456 + 458 - 9157346 + 13638546 double epsilon_ratio = input_epsilon / max_TE; - 457 + 459 - 458 + 460 - 9157346 + 13638546 double h_new = 0.9 * input_step_size * std::pow(epsilon_ratio, 1.0 / 5); - 459 + 461 - 460 + 462
2/2
-
✓ Branch 0 taken 209337 times.
-
✓ Branch 1 taken 8948009 times.
+
✓ Branch 0 taken 1171628 times.
+
✓ Branch 1 taken 12466918 times.
- 9157346 + 13638546 if (max_TE <= input_epsilon) { - 461 + 463 - 8948009 + 12466918 std::pair<double, double> output_timestep_pair; - 462 + 464 - 8948009 + 12466918 output_timestep_pair.first = - 463 + 465 - 8948009 + 12466918 input_step_size; // First timestep size in this pair is the one - 464 + 466 // successfully used in this calculation - 465 + 467 - 8948009 + 12466918 output_timestep_pair.second = - 466 + 468 - 8948009 + 12466918 h_new; // Second timestep size in this pair is the one to be used in - 467 + 469 // the next step - 468 + 470 - 8948009 + 12466918 std::pair<std::array<double, T>, std::pair<double, double>> output_pair; - 469 + 471 - 8948009 + 12466918 output_pair.first = y_nplusone; - 470 + 472 - 8948009 + 12466918 output_pair.second = output_timestep_pair; - 471 + 473 - 8948009 + 12466918 return output_pair; - 472 + 474 } else { - 473 + 475
1/2
-
✓ Branch 0 taken 209337 times.
+
✓ Branch 0 taken 1171628 times.
✗ Branch 1 not taken.
- 209337 + 1171628 return RK45_step<T>( - 474 + 476
2/4
-
✓ Branch 0 taken 209337 times.
+
✓ Branch 0 taken 1171628 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 209337 times.
+
✓ Branch 2 taken 1171628 times.
✗ Branch 3 not taken.
- 209337 + 1171628 y_n, h_new, input_combined_derivative_function, J_matrix, - 475 + 477
2/4
-
✓ Branch 0 taken 209337 times.
+
✓ Branch 0 taken 1171628 times.
✗ Branch 1 not taken.
-
✓ Branch 2 taken 209337 times.
+
✓ Branch 2 taken 1171628 times.
✗ Branch 3 not taken.
- 209337 + 1171628 input_bodyframe_torque_profile_list, input_omega_I, - 476 + 478 - 209337 + 1171628 input_orbital_angular_acceleration, - 477 + 479
1/2
-
✓ Branch 0 taken 209337 times.
+
✓ Branch 0 taken 1171628 times.
✗ Branch 1 not taken.
- 209337 + 1171628 input_LVLH_to_bodyframe_transformation_matrix, - 478 + 480
1/2
-
✓ Branch 0 taken 209337 times.
+
✓ Branch 0 taken 1171628 times.
✗ Branch 1 not taken.
- 209337 + 1171628 input_omega_LVLH_wrt_inertial_in_LVLH, input_spacecraft_mass, - 479 + 481
1/2
-
✓ Branch 0 taken 209337 times.
+
✓ Branch 0 taken 1171628 times.
✗ Branch 1 not taken.
- 209337 + 1171628 input_list_of_thrust_profiles_LVLH, input_inclination, - - 480 - - - 209337 - input_arg_of_periapsis, input_true_anomaly, input_F_10, input_A_p, - - - 481 - - - 209337 - input_A_s, perturbation, atmospheric_drag, input_t_n, input_epsilon); - 482 - - } + 1171628 + input_arg_of_periapsis, input_true_anomaly, input_F_10, input_A_p, 483 - 9157346 - } + 1171628 + input_A_s, perturbation, atmospheric_drag, input_t_n, input_epsilon); 484 - Vector3d calculate_omega_I( + } 485 - - const Vector3d input_bodyframe_ang_vel_vector_wrt_lvlh, + 13638546 + } 486 - const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, + Vector3d calculate_omega_I( 487 - const double input_orbital_rate); + const Vector3d input_bodyframe_ang_vel_vector_wrt_lvlh, 488 - + const Matrix3d input_LVLH_to_bodyframe_transformation_matrix, 489 - Matrix3d construct_J_matrix(const double input_Jxx, const double input_Jyy, + const double input_orbital_rate); 490 - const double input_Jzz); + 491 - + Matrix3d construct_J_matrix(const double input_Jxx, const double input_Jyy, 492 - std::array<double, 3> convert_quaternion_to_roll_yaw_pitch_angles( + const double input_Jzz); 493 - const std::array<double, 4>); + 494 - + std::array<double, 3> convert_quaternion_to_roll_yaw_pitch_angles( 495 - std::array<double, 4> normalize_quaternion( + const std::array<double, 4>); 496 - std::array<double, 4> input_quaternion); + 497 - + std::array<double, 4> normalize_quaternion( 498 - std::array<double, 3> convert_array_from_LVLH_to_bodyframe( + std::array<double, 4> input_quaternion); 499 - const std::array<double, 3> input_LVLH_frame_array, const double input_roll, + 500 - const double input_yaw, const double input_pitch); + std::array<double, 3> convert_array_from_LVLH_to_bodyframe( 501 - + const std::array<double, 3> input_LVLH_frame_array, const double input_roll, 502 - + const double input_yaw, const double input_pitch); 503 - Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, const double height); + 504 - Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, const double input_time); + Vector3d convert_lat_long_to_ECEF(const double latitude, const double longitude, 505 - + const double height); 506 - void sim_and_plot_gs_connectivity_distance_gnuplot(PhasedArrayGroundStation input_ground_station, + Vector3d convert_ECEF_to_ECI(const Vector3d input_ECEF_position, 507 - std::vector<Satellite> input_satellite_vector, + const double input_time); 508 - const SimParameters& input_sim_parameters, + 509 - const std::string file_name = "output"); + void sim_and_plot_gs_connectivity_distance_gnuplot( 510 - + PhasedArrayGroundStation input_ground_station, 511 - void sim_and_plot_gs_connectivity_gnuplot(PhasedArrayGroundStation input_ground_station, + std::vector<Satellite> input_satellite_vector, 512 - std::vector<Satellite> input_satellite_vector, + const SimParameters& input_sim_parameters, 513 - const SimParameters& input_sim_parameters, + const std::string file_name = "output"); 514 - const std::string file_name = "output"); + 515 - + void sim_and_plot_gs_connectivity_gnuplot( 516 - int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, const double final_orbit_semimajor_axis_km, + PhasedArrayGroundStation input_ground_station, 517 - const double thrust_magnitude, const double transfer_initiation_time = 0); + std::vector<Satellite> input_satellite_vector, 518 - + const SimParameters& input_sim_parameters, 519 - double calibrate_mean_val(Satellite satellite_object, const SimParameters& input_sim_parameters, const std::string input_parameter_name); + const std::string file_name = "output"); 520 - #endif + 521 + int add_lowthrust_orbit_transfer(Satellite& input_satellite_object, + + + 522 + + + + const double final_orbit_semimajor_axis_km, + + + 523 + + + + const double thrust_magnitude, + + + 524 + + + + const double transfer_initiation_time = 0); + + + 525 + + + + #endif + + + 526 + + + diff --git a/tests/test_coverage_summary.json b/tests/test_coverage_summary.json index 8465c80..46b986c 100644 --- a/tests/test_coverage_summary.json +++ b/tests/test_coverage_summary.json @@ -1 +1 @@ -{"root": "..", "gcovr/summary_format_version": "0.6", "files": [{"filename": "include/PhasedArrayGroundStation.h", "line_total": 10, "line_covered": 10, "line_percent": 100.0, "function_total": 3, "function_covered": 3, "function_percent": 100.0, "branch_total": 2, "branch_covered": 1, "branch_percent": 50.0}, {"filename": "include/Satellite.h", "line_total": 193, "line_covered": 179, "line_percent": 92.7, "function_total": 20, "function_covered": 19, "function_percent": 95.0, "branch_total": 176, "branch_covered": 107, "branch_percent": 60.8}, {"filename": "include/utils.h", "line_total": 129, "line_covered": 121, "line_percent": 93.8, "function_total": 3, "function_covered": 3, "function_percent": 100.0, "branch_total": 222, "branch_covered": 113, "branch_percent": 50.9}, {"filename": "src/PhasedArrayGroundStation.cpp", "line_total": 75, "line_covered": 74, "line_percent": 98.7, "function_total": 6, "function_covered": 6, "function_percent": 100.0, "branch_total": 57, "branch_covered": 41, "branch_percent": 71.9}, {"filename": "src/Satellite.cpp", "line_total": 388, "line_covered": 365, "line_percent": 94.1, "function_total": 20, "function_covered": 19, "function_percent": 95.0, "branch_total": 108, "branch_covered": 87, "branch_percent": 80.6}, {"filename": "src/utils.cpp", "line_total": 971, "line_covered": 869, "line_percent": 89.5, "function_total": 29, "function_covered": 28, "function_percent": 96.6, "branch_total": 756, "branch_covered": 435, "branch_percent": 57.5}], "line_total": 1766, "line_covered": 1618, "line_percent": 91.6, "function_total": 81, "function_covered": 78, "function_percent": 96.3, "branch_total": 1321, "branch_covered": 784, "branch_percent": 59.3} \ No newline at end of file +{"root": "..", "gcovr/summary_format_version": "0.6", "files": [{"filename": "include/PhasedArrayGroundStation.h", "line_total": 11, "line_covered": 11, "line_percent": 100.0, "function_total": 3, "function_covered": 3, "function_percent": 100.0, "branch_total": 2, "branch_covered": 1, "branch_percent": 50.0}, {"filename": "include/Satellite.h", "line_total": 201, "line_covered": 201, "line_percent": 100.0, "function_total": 20, "function_covered": 20, "function_percent": 100.0, "branch_total": 178, "branch_covered": 110, "branch_percent": 61.8}, {"filename": "include/utils.h", "line_total": 129, "line_covered": 121, "line_percent": 93.8, "function_total": 3, "function_covered": 3, "function_percent": 100.0, "branch_total": 222, "branch_covered": 113, "branch_percent": 50.9}, {"filename": "src/PhasedArrayGroundStation.cpp", "line_total": 79, "line_covered": 78, "line_percent": 98.7, "function_total": 6, "function_covered": 6, "function_percent": 100.0, "branch_total": 57, "branch_covered": 41, "branch_percent": 71.9}, {"filename": "src/Satellite.cpp", "line_total": 425, "line_covered": 406, "line_percent": 95.5, "function_total": 22, "function_covered": 21, "function_percent": 95.5, "branch_total": 130, "branch_covered": 104, "branch_percent": 80.0}, {"filename": "src/utils.cpp", "line_total": 996, "line_covered": 913, "line_percent": 91.7, "function_total": 28, "function_covered": 28, "function_percent": 100.0, "branch_total": 746, "branch_covered": 437, "branch_percent": 58.6}], "line_total": 1841, "line_covered": 1730, "line_percent": 94.0, "function_total": 82, "function_covered": 81, "function_percent": 98.8, "branch_total": 1335, "branch_covered": 806, "branch_percent": 60.4} \ No newline at end of file From 2457405d683434897526371cd35bf74d8d9ef269 Mon Sep 17 00:00:00 2001 From: Connor Powers <20464743+connor-powers@users.noreply.github.com> Date: Wed, 7 May 2025 03:16:11 -0700 Subject: [PATCH 7/7] Update Satellite.h Manually adjusting some formatting I didn't like --- include/Satellite.h | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/include/Satellite.h b/include/Satellite.h index 1e5528e..edce6f3 100644 --- a/include/Satellite.h +++ b/include/Satellite.h @@ -19,14 +19,16 @@ using json = nlohmann::json; class ThrustProfileLVLH { // Note: for now, thrust forces are assumed to act through center of mass of - // satellite. + // the satellite. public: double t_start_ = {0}; double t_end_ = {0}; bool arg_of_periapsis_change_thrust_profile = false; + // ======================================================================= + // Only used for argument of periapsis change thrust profiles double sign_of_delta_omega = {1}; - double thrust_magnitude_ = { - 0}; // Only used for argument of periapsis change thrust profiles + double thrust_magnitude_ = {0}; + // ======================================================================= std::array LVLH_force_vec_ = {0, 0, 0}; ThrustProfileLVLH(const double t_start, const double t_end, const std::array LVLH_force_vec) { @@ -52,7 +54,6 @@ class ThrustProfileLVLH { const double satellite_a, const double satellite_mass) { // Thrust profile for continuous-thrust argument of periapsis change // Main ref: https://apps.dtic.mil/sti/tr/pdf/ADA384536.pdf - // // Used Eq. 67 in // https://link.springer.com/article/10.1007/s10569-021-10033-9#Sec15 to // determine burn angles Arguments of periapsis are input in radians @@ -117,23 +118,24 @@ class BodyframeTorqueProfile { class Satellite { private: double inclination_ = {0}; - double raan_ = { - 0}; // Assuming RAAN can be used interchangeably with longitude of - // ascending node for the Earth-orbiting satellites simulated here + double raan_ = {0}; + // Assuming RAAN can be used interchangeably with longitude of + // ascending node for the Earth-orbiting satellites simulated here double arg_of_periapsis_ = {0}; double eccentricity_ = {0}; double a_ = {0}; double true_anomaly_ = {0}; double orbital_period_ = {0}; - double m_ = {1}; // default value to prevent infinities in acceleration - // calculations from a=F/m + double m_ = {1}; + // default value to prevent infinities in acceleration + // calculations from a=F/m // double I_={1}; //moment of inertia, taken to be same for all 3 principal // axes, set to default value for same reasons as mass double t_ = {0}; double orbital_rate_ = {0}; - double orbital_angular_acceleration_ = {0}; // Time derivative of orbital - // rate + // Time derivative of orbital rate + double orbital_angular_acceleration_ = {0}; // Now body-frame attributes // Assuming diagonal J matrix @@ -152,8 +154,8 @@ class Satellite { // body-frame angular velocities relative to the LVLH frame, represented in // the body frame - std::array body_angular_velocity_vec_wrt_LVLH_in_body_frame_ = { - 0, 0, 0}; + std::array body_angular_velocity_vec_wrt_LVLH_in_body_frame_ + = {0, 0, 0}; // quaternion representing attitude of satellite body frame with respect to // the LVLH frame