├── LICENSE ├── README.md └── project_phd ├── CMakeLists.txt ├── inputs ├── env_test │ ├── test_double1.txt │ ├── test_double2.txt │ └── test_double3.txt └── seeds │ └── seeds.txt ├── matlab_display ├── display_control_lat.m ├── display_control_long.m ├── display_debug.m ├── display_filter_air_atm.m ├── display_filter_air_vbfs.m ├── display_filter_att_Egyr.m ├── display_filter_att_Emag01.m ├── display_filter_att_Emag02.m ├── display_filter_att_bias_acc.m ├── display_filter_att_euler.m ├── display_filter_att_obs_acc.m ├── display_filter_att_obs_gyr.m ├── display_filter_att_obs_mag.m ├── display_filter_att_qnb.m ├── display_filter_att_wnbb.m ├── display_filter_pos_Eacc.m ├── display_filter_pos_fibb.m ├── display_filter_pos_obs_acc.m ├── display_filter_pos_obs_vned.m ├── display_filter_pos_obs_xgdt.m ├── display_filter_pos_vned.m ├── display_filter_pos_wind_DeltaTp.m ├── display_filter_pos_xgdt.m ├── display_michael.m ├── display_output_pos.m ├── display_sens_inertial.m └── display_sens_other.m ├── outputs └── outputs_go_here.txt └── phd ├── CMakeLists.txt ├── acft ├── CMakeLists.txt ├── acft.h ├── acft │ ├── aero.h │ ├── aero0.cpp │ ├── aero0.h │ ├── aero1.cpp │ ├── aero1.h │ ├── aero2.cpp │ ├── aero2.h │ ├── aero3.cpp │ ├── aero3.h │ ├── iner.cpp │ ├── iner.h │ ├── prop.cpp │ └── prop.h ├── control │ ├── cntr.cpp │ ├── cntr.h │ ├── logic.h │ ├── pid.h │ ├── pid_factory.cpp │ ├── pid_factory.h │ ├── pid_functor.h │ ├── pid_mimo.cpp │ ├── pid_mimo.h │ ├── pid_p.cpp │ ├── pid_p.h │ ├── pid_prim.cpp │ ├── pid_prim.h │ ├── pid_secnd.cpp │ └── pid_secnd.h ├── guid │ ├── guid.cpp │ ├── guid.h │ ├── trg.cpp │ └── trg.h ├── sens │ ├── camera.cpp │ ├── camera.h │ ├── logic.h │ ├── platform.cpp │ ├── platform.h │ ├── sens_single_inertial.cpp │ ├── sens_single_inertial.h │ ├── sens_single_no_walk.cpp │ ├── sens_single_no_walk.h │ ├── sens_single_noise.cpp │ ├── sens_single_noise.h │ ├── sens_single_one_use.cpp │ ├── sens_single_one_use.h │ ├── sens_triple_acc.cpp │ ├── sens_triple_acc.h │ ├── sens_triple_gps.cpp │ ├── sens_triple_gps.h │ ├── sens_triple_gyr.cpp │ ├── sens_triple_gyr.h │ ├── sens_triple_mag.cpp │ ├── sens_triple_mag.h │ ├── suite.cpp │ └── suite.h └── st │ ├── st_extra.h │ ├── sti.cpp │ ├── sti.h │ ├── trj.h │ ├── trj_cntr.h │ ├── trj_gps_out.h │ ├── trj_nav_in.h │ ├── trj_nav_out.h │ ├── trj_out.h │ ├── trj_sens_in.h │ ├── trj_sens_out.h │ └── trj_truth.h ├── acft_test ├── CMakeLists.txt ├── Tapm.cpp ├── Tapm.h ├── Tapm_plots.cpp ├── Tapm_plots.h ├── Tbrick.cpp ├── Tbrick.h ├── Tsensor.cpp ├── Tsensor.h ├── Tsti.cpp ├── Tsti.h ├── acft_test.h └── main.cpp ├── ang ├── CMakeLists.txt ├── ang.h ├── auxiliary.h ├── quat.h ├── references.h ├── rotate │ ├── dcm.cpp │ ├── dcm.h │ ├── euler.cpp │ ├── euler.h │ ├── rodrigues.cpp │ ├── rodrigues.h │ ├── rotv.cpp │ ├── rotv.h │ ├── so3.cpp │ └── so3.h ├── tools.cpp └── tools.h ├── ang_test ├── CMakeLists.txt ├── Tcheck.cpp ├── Tcheck.h ├── Tintegration.cpp ├── Tintegration.h ├── Tso3.cpp ├── Tso3.h ├── Tspecific.cpp ├── Tspecific.h ├── ang_test.h └── main.cpp ├── configuration ├── apm │ ├── OLDmugin_aerodynamics0_cpp.txt │ ├── OLDmugin_inertia_python.txt │ ├── OLDmugin_propulsion_python.txt │ ├── mugin_aerodynamics0_cpp.txt │ ├── mugin_aerodynamics1_cpp.txt │ ├── mugin_aerodynamics2_cpp.txt │ ├── mugin_aerodynamics3_cpp.txt │ ├── mugin_inertia_cpp.txt │ ├── mugin_propeller.txt │ └── mugin_propulsion_cpp.txt └── geopotential │ ├── H2h_32_geom.txt │ ├── H2h_32_geop.txt │ ├── H2h_32_lat.txt │ ├── htoH_32_geom.txt │ ├── htoH_32_geop.txt │ ├── htoH_32_lat.txt │ └── htoH_python.txt ├── env ├── CMakeLists.txt ├── atm.cpp ├── atm.h ├── coord.cpp ├── coord.h ├── earth.cpp ├── earth.h ├── env.h ├── geo.cpp ├── geo.h ├── geo2.cpp ├── mag.cpp ├── mag.h ├── offsets.cpp ├── offsets.h ├── speed.cpp ├── speed.h ├── turb.cpp ├── turb.h ├── wind.cpp └── wind.h ├── env_test ├── CMakeLists.txt ├── Tenv_plots_phd.cpp ├── Tenv_plots_phd.h ├── Tenvironment.cpp ├── Tenvironment.h ├── Tgravity.cpp ├── Tgravity.h ├── Tmagnetic.cpp ├── Tmagnetic.h ├── Tturb.cpp ├── Tturb.h ├── env_test.h └── main.cpp ├── exec_cntr ├── CMakeLists.txt └── main.cpp ├── exec_gps_alter ├── CMakeLists.txt └── main.cpp ├── exec_gps_alter_mult ├── CMakeLists.txt └── main.cpp ├── exec_gps_bench ├── CMakeLists.txt └── main.cpp ├── exec_gps_bench_mult ├── CMakeLists.txt └── main.cpp ├── exec_nav ├── CMakeLists.txt └── main.cpp ├── jail ├── CMakeLists.txt ├── jail.h ├── unit_test.cpp └── unit_test.h ├── math ├── CMakeLists.txt ├── classifiers.h ├── interp │ ├── hermite.cpp │ ├── hermite.h │ ├── hermite_pow.cpp │ ├── hermite_pow.h │ ├── interp.cpp │ ├── interp.h │ ├── interp_biparabolic.cpp │ ├── interp_biparabolic.h │ ├── interp_hermite.cpp │ ├── interp_hermite.h │ ├── interp_lagrange_first.cpp │ ├── interp_lagrange_first.h │ ├── interp_lagrange_second.cpp │ ├── interp_lagrange_second.h │ ├── interp_lagrange_third.cpp │ ├── interp_lagrange_third.h │ ├── interp_spline.cpp │ ├── interp_spline.h │ ├── ratio.cpp │ ├── ratio.h │ ├── ratio_mgr.cpp │ └── ratio_mgr.h ├── logic │ ├── constant.cpp │ ├── constant.h │ ├── logic.h │ ├── seeder.cpp │ ├── seeder.h │ ├── share.cpp │ ├── share.h │ └── timer.h ├── math.h ├── math │ ├── func.cpp │ ├── func.h │ ├── linear_fit_lsq.cpp │ ├── linear_fit_lsq.h │ ├── low_pass.cpp │ └── low_pass.h ├── pred │ ├── classifiers.h │ ├── pos_finder.cpp │ ├── pos_finder.h │ ├── pred.cpp │ ├── pred.h │ ├── pred0v │ │ └── pred0v.h │ ├── pred1v │ │ ├── f_table1V.cpp │ │ ├── f_table1V.h │ │ └── pred1v.h │ ├── pred2v │ │ ├── f_table2V.cpp │ │ ├── f_table2V.h │ │ └── pred2v.h │ ├── pred3v │ │ ├── f_table3V.cpp │ │ ├── f_table3V.h │ │ └── pred3v.h │ ├── range_checker.cpp │ └── range_checker.h ├── templates │ ├── factory_.h │ ├── math_.h │ ├── metrics_.h │ ├── nlls_gauss_newton_.h │ ├── nlls_gauss_newton_.hpp │ ├── pool_.h │ └── singleton_holder_.h └── vec │ ├── algorithm.cpp │ ├── algorithm.h │ ├── classifiers.h │ ├── vec.cpp │ ├── vec.h │ ├── vec1.cpp │ ├── vec1.h │ ├── vec2.cpp │ ├── vec2.h │ ├── vec3.cpp │ ├── vec3.h │ ├── vec4.cpp │ └── vec4.h ├── nav ├── CMakeLists.txt ├── air │ ├── filter_air.h │ ├── filter_air01.cpp │ ├── filter_air01.h │ ├── filter_air01b.cpp │ ├── filter_air02.cpp │ ├── filter_air02.h │ └── filter_air02b.cpp ├── att │ ├── filter_att.h │ ├── filter_att01.cpp │ ├── filter_att01.h │ ├── filter_att01b.cpp │ ├── filter_att02.cpp │ ├── filter_att02.h │ ├── filter_att02b.cpp │ ├── filter_att03.cpp │ ├── filter_att03.h │ ├── filter_att03b.cpp │ ├── filter_att04.cpp │ ├── filter_att04.h │ └── filter_att04b.cpp ├── gps │ ├── filter_gps.h │ ├── filter_gps01.cpp │ ├── filter_gps01.h │ └── filter_gps01b.cpp ├── init │ ├── align_coarse.cpp │ ├── align_coarse.h │ ├── error_gen_att.cpp │ ├── error_gen_att.h │ ├── error_gen_triple.cpp │ ├── error_gen_triple.h │ ├── init_error.cpp │ ├── init_error.h │ └── logic.h ├── kalman │ ├── ekf_.h │ ├── ekf_functor_.h │ ├── ekf_handler_.h │ ├── ekfd_.h │ ├── ekfd_handler_.h │ ├── kf_.h │ └── kf_handler_.h ├── motion │ ├── motion.cpp │ ├── motion.h │ ├── motion2.cpp │ ├── textplot.cpp │ └── textplot.h ├── nav.h ├── nav │ ├── filter_nav.cpp │ └── filter_nav.h └── pos │ ├── filter_pos.cpp │ ├── filter_pos.h │ ├── filter_pos01.cpp │ ├── filter_pos01.h │ ├── filter_pos02.cpp │ ├── filter_pos02.h │ ├── filter_pos03.cpp │ ├── filter_pos03.h │ └── filter_posb.cpp ├── nav_test ├── CMakeLists.txt ├── Talign_coarse.cpp ├── Talign_coarse.h ├── Tsimple.cpp ├── Tsimple.h ├── Ttrj_sizes.cpp ├── Ttrj_sizes.h ├── main.cpp └── nav_test.h ├── results_ana_test ├── CMakeLists.txt ├── Tplots_att_filter.cpp ├── Tplots_att_filter.h ├── Tplots_att_filter_alter.cpp ├── Tplots_att_filter_alter.h ├── Tplots_gnss.cpp ├── Tplots_gnss.h ├── Tplots_init.cpp ├── Tplots_init.h ├── Tplots_pos_filter.cpp ├── Tplots_pos_filter.h ├── Tplots_sensors_acc.cpp ├── Tplots_sensors_acc.h ├── Tplots_sensors_air.cpp ├── Tplots_sensors_air.h ├── Tplots_sensors_bias.cpp ├── Tplots_sensors_bias.h ├── Tplots_sensors_gyr.cpp ├── Tplots_sensors_gyr.h ├── Tplots_sensors_mag.cpp ├── Tplots_sensors_mag.h ├── Tplots_sensors_vtasb.cpp ├── Tplots_sensors_vtasb.h ├── main.cpp └── results_ana_test.h └── results_sim_test ├── CMakeLists.txt ├── Tplots_air.cpp ├── Tplots_air.h ├── Tplots_attitude.cpp ├── Tplots_attitude.h ├── Tplots_control.cpp ├── Tplots_control.h ├── Tplots_number.cpp ├── Tplots_number.h ├── Tplots_pos.cpp ├── Tplots_pos.h ├── Tplots_seeds.cpp ├── Tplots_seeds.h ├── main.cpp └── results_sim_test.h /README.md: -------------------------------------------------------------------------------- 1 | # gnssdenied_flight_simulation 2 | High fidelity flight simulation for an autonomous low SWaP (Size, Weight, and Power) fixed wing unmanned air vehicle in GNSS-Denied conditions. 3 | 4 | It is necessary to set four different global variables: 5 | GIT_CONFIGURATION_PREFIX should point to the provided project_phd/phd/configuration folder. 6 | GIT_INPUTS_PREFIX should point ot the provided project_phd/inputs folder. 7 | GIT_OUTPUTS_PREFIX should point ot the provided project_phd/outputs folder. 8 | GIT_OUTPUTS_STORE_PREFIX should also point ot the provided project_phd/outputs folder. 9 | 10 | Matlab files are intended to visualize the trajectory results. 11 | 12 | Big files containing preloaded turbulence values are required to obtain a trajectory. Please ask author through edugallo@yahoo.com if interested. 13 | -------------------------------------------------------------------------------- /project_phd/inputs/env_test/test_double1.txt: -------------------------------------------------------------------------------- 1 | 23.5 2 | 4.2 3 | 6 -------------------------------------------------------------------------------- /project_phd/inputs/env_test/test_double2.txt: -------------------------------------------------------------------------------- 1 | 4 2 | 3 3 | 1.0 2.0 4.0 8.0 4 | 10.0 20.0 40.0 80.0 5 | 100.0 200.0 400.0 800.0 6 | -------------------------------------------------------------------------------- /project_phd/inputs/env_test/test_double3.txt: -------------------------------------------------------------------------------- 1 | 5 2 | 4 3 | 3 4 | 1.0 2.0 4.0 8.0 16.0 5 | 10.0 20.0 40.0 80.0 160.0 6 | 100.0 200.0 400.0 800.0 1600.0 7 | 1000.0 2000.0 4000.0 8000.0 16000.0 8 | 1.5 2.5 4.5 8.5 16.5 9 | 15.0 25.0 45.0 85.0 165.0 10 | 150.0 250.0 450.0 850.0 1650.0 11 | 1500.0 2500.0 4500.0 8500.0 16500.0 12 | 2.0 3.0 5.0 9.0 17.0 13 | 20.0 30.0 50.0 90.0 170.0 14 | 200.0 300.0 500.0 900.0 1700.0 15 | 2000.0 3000.0 5000.0 9000.0 17000.0 -------------------------------------------------------------------------------- /project_phd/inputs/seeds/seeds.txt: -------------------------------------------------------------------------------- 1 | 1127814431 2 | 655930988 3 | 1491640902 4 | 1208772778 5 | 1124981204 6 | 2114556507 7 | 324893749 8 | 339764579 9 | 12294765 10 | 408230666 11 | 936693798 12 | 1497084908 13 | 1342656579 14 | 1487070208 15 | 1080850627 16 | 1858627451 17 | 355326488 18 | 1375583719 19 | 1162176459 20 | 724308832 21 | 1829555470 22 | 2111356685 23 | 422112705 24 | 1812575198 25 | 1529135900 26 | 359262478 27 | 1030506058 28 | 727746117 29 | 1457248710 30 | 153552181 31 | 1327792450 32 | 289420010 33 | 1028897078 34 | 1476598456 35 | 1878923123 36 | 1645923683 37 | 907767757 38 | 669634600 39 | 462869614 40 | 1151177006 41 | 205452189 42 | 754215576 43 | 1489325797 44 | 173449604 45 | 122279928 46 | 859560164 47 | 1039553316 48 | 1974108545 49 | 1396388278 50 | 1600128975 51 | 396690550 52 | 2035859957 53 | 1768656356 54 | 642172702 55 | 110803178 56 | 223240946 57 | 1896802813 58 | 909096192 59 | 1766880249 60 | 284178280 61 | 957559099 62 | 313451054 63 | 512405642 64 | 1895281155 65 | 646228355 66 | 332163613 67 | 185870660 68 | 289164696 69 | 2129184773 70 | 1884615810 71 | 712767011 72 | 2065953243 73 | 1462312028 74 | 1798956503 75 | 1372210168 76 | 964969503 77 | 1419724888 78 | 1130148415 79 | 1596308627 80 | 1083045472 81 | 1000045593 82 | 1665815509 83 | 434158620 84 | 1677839031 85 | 1768217091 86 | 1331795521 87 | 310382557 88 | 1599895548 89 | 274891359 90 | 621291460 91 | 1866193325 92 | 1374820732 93 | 616627171 94 | 739782281 95 | 187132840 96 | 188354294 97 | 1754087288 98 | 1415538081 99 | 446176940 100 | 734720939 101 | -------------------------------------------------------------------------------- /project_phd/matlab_display/display_debug.m: -------------------------------------------------------------------------------- 1 | function display_debug() 2 | 3 | fileID = fopen('/home/egallo/utm/trunk/phd/outputs/flight_test/debug.txt'); 4 | uavTruth = textscan(fileID, '%f %f %f','Delimiter',' ','MultipleDelimsAsOne',1); 5 | fclose(fileID); 6 | %plot_name = 'plot_uavTruth_theta_vtas'; 7 | 8 | t_sec = uavTruth{1}; 9 | vtas_err_mps = uavTruth{2}; 10 | vtas_err_lpf_mps = uavTruth{3}; 11 | clear uavTruth; 12 | 13 | h = figure('units','normalized','position',[0 0.15 1.0 0.85]); 14 | 15 | ax1 = subplot(2,2,1); 16 | l = plot(t_sec, [vtas_err_mps vtas_err_lpf_mps]); hold on; 17 | xlabel('t [sec]'); 18 | %ylabel(hAx(1),'\theta [deg]'); 19 | %ylabel(hAx(2),'\delta_{E} [deg]'); 20 | l(1).Color = 'k'; 21 | %hLine1(1).LineWidth = 1.5; 22 | l(2).Color = 'b'; 23 | %hLine1(2).LineStyle = '-.'; 24 | %hLine1(2).LineWidth = 1.5; 25 | %hLine2.Color = 'b'; 26 | %hLine2.LineWidth = 1.5; 27 | %hAx(1).YColor = 'k'; 28 | %hAx(2).YColor = 'b'; 29 | %hAx(1).XMinorGrid = 'on'; 30 | %hAx(1).YMinorGrid = 'on'; 31 | %hAx(2).YMinorGrid = 'on'; 32 | grid on; 33 | 34 | ax2 = subplot(2,2,2); 35 | grid on; 36 | 37 | ax4 = subplot(2,2,3); 38 | grid on; 39 | 40 | ax3 = subplot(2,2,4); 41 | grid on; 42 | 43 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 44 | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 45 | -------------------------------------------------------------------------------- /project_phd/outputs/outputs_go_here.txt: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /project_phd/phd/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname phd_member) 3 | set(version 1) 4 | 5 | project(${prjname} CXX) 6 | add_subdirectory(jail) 7 | add_subdirectory(math) 8 | add_subdirectory(ang) 9 | add_subdirectory(ang_test) 10 | add_subdirectory(env) 11 | add_subdirectory(env_test) 12 | add_subdirectory(acft) 13 | add_subdirectory(acft_test) 14 | add_subdirectory(nav) 15 | add_subdirectory(nav_test) 16 | add_subdirectory(results_sim_test) 17 | add_subdirectory(results_ana_test) 18 | add_subdirectory(exec_nav) 19 | add_subdirectory(exec_gps_bench) 20 | add_subdirectory(exec_gps_bench_mult) 21 | add_subdirectory(exec_gps_alter) 22 | add_subdirectory(exec_gps_alter_mult) 23 | add_subdirectory(exec_cntr) 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /project_phd/phd/acft/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname acft) 3 | 4 | file (GLOB dir_10_headers *.h *.hpp) 5 | file (GLOB dir_11_headers acft/*.h acft/*.hpp) 6 | file (GLOB dir_12_headers control/*.h control/*.hpp) 7 | file (GLOB dir_13_headers guid/*.h guid/*.hpp) 8 | file (GLOB dir_15_headers sens/*.h sens/*.hpp) 9 | file (GLOB dir_16_headers st/*.h st/*.hpp) 10 | 11 | source_group("" FILES ${dir_10_headers}) 12 | source_group("acft" FILES ${dir_11_headers}) 13 | source_group("control" FILES ${dir_12_headers}) 14 | source_group("guid" FILES ${dir_13_headers}) 15 | source_group("sens" FILES ${dir_15_headers}) 16 | source_group("st" FILES ${dir_16_headers}) 17 | set(all_headers ${dir_10_headers} ${dir_11_headers} ${dir_12_headers} ${dir_13_headers} ${dir_15_headers} ${dir_16_headers} ) 18 | 19 | file (GLOB dir_10_sources *.cpp *.c *.cxx) 20 | file (GLOB dir_11_sources acft/*.cpp acft/*.c acft/*.cxx) 21 | file (GLOB dir_12_sources control/*.cpp control/*.c control/*.cxx) 22 | file (GLOB dir_13_sources guid/*.cpp guid/*.c guid/*.cxx) 23 | file (GLOB dir_15_sources sens/*.cpp sens/*.c sens/*.cxx) 24 | file (GLOB dir_16_sources st/*.cpp st/*.c st/*.cxx) 25 | source_group("" FILES ${dir_10_sources}) 26 | source_group("acft" FILES ${dir_11_sources}) 27 | source_group("control" FILES ${dir_12_sources}) 28 | source_group("guid" FILES ${dir_13_sources}) 29 | source_group("sens" FILES ${dir_15_sources}) 30 | source_group("st" FILES ${dir_16_sources}) 31 | set(all_sources ${dir_10_sources} ${dir_11_sources} ${dir_12_sources} ${dir_13_sources} ${dir_15_sources} ${dir_16_sources} ) 32 | 33 | string(TOUPPER ${prjname} PRJNAME) 34 | add_definitions(-D${PRJNAME}_DLL) 35 | add_definitions(-D${PRJNAME}_DLL_EXPORTS) 36 | 37 | add_library(${prjname} SHARED ${all_headers} ${all_sources}) 38 | 39 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 40 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 41 | 42 | include_directories(${PROJECTS_SRC_ROOT}/phd) 43 | 44 | # Following lines are for Windows compatibility 45 | add_definitions(-DATTITUDE_DLL) 46 | # End Windows compatibility 47 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 48 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 49 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 50 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 51 | 52 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 53 | target_link_libraries(${prjname} optimized ${A_LIB}) # adds all Eigen libraries to target 54 | endforeach() 55 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 56 | target_link_libraries(${prjname} debug ${A_LIB}) # adds all Eigen libraries to target 57 | endforeach() 58 | 59 | 60 | 61 | 62 | 63 | -------------------------------------------------------------------------------- /project_phd/phd/acft/acft.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Generic helper definitions for shared library support 4 | #if defined _WIN32 || defined __CYGWIN__ 5 | #define ACFT_HELPER_DLL_IMPORT __declspec(dllimport) 6 | #define ACFT_HELPER_DLL_EXPORT __declspec(dllexport) 7 | #define ACFT_HELPER_DLL_LOCAL 8 | #else 9 | #if __GNUC__ >= 4 10 | #define ACFT_HELPER_DLL_IMPORT __attribute__ ((visibility ("default"))) 11 | #define ACFT_HELPER_DLL_EXPORT __attribute__ ((visibility ("default"))) 12 | #define ACFT_HELPER_DLL_LOCAL __attribute__ ((visibility ("hidden"))) 13 | #else 14 | #define ACFT_HELPER_DLL_IMPORT 15 | #define ACFT_HELPER_DLL_EXPORT 16 | #define ACFT_HELPER_DLL_LOCAL 17 | #endif 18 | #endif 19 | 20 | // Now we use the generic helper definitions above to define ACFT_API and ACFT_LOCAL. 21 | // ACFT_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 22 | // ACFT_LOCAL is used for non-api symbols. 23 | 24 | #ifdef ACFT_DLL // defined if ACFT is compiled as a DLL 25 | #ifdef ACFT_DLL_EXPORTS // defined if we are building the ACFT DLL (instead of using it) 26 | #define ACFT_API ACFT_HELPER_DLL_EXPORT 27 | #else 28 | #define ACFT_API ACFT_HELPER_DLL_IMPORT 29 | #endif // ACFT_DLL_EXPORTS 30 | #define ACFT_LOCAL ACFT_HELPER_DLL_LOCAL 31 | #else // ACFT_DLL is not defined: this means ACFT is a static lib. 32 | #define ACFT_API 33 | #define ACFT_LOCAL 34 | #endif // ACFT_DLL 35 | -------------------------------------------------------------------------------- /project_phd/phd/acft/acft/aero.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_AERO 2 | #define ACFT_AERO 3 | 4 | #include "../acft.h" 5 | #include "aero.h" 6 | #include "ang/rotate/euler.h" 7 | #include 8 | 9 | /* 10 | * This file contains the Aerodynamic Force Model base class. 11 | */ 12 | 13 | namespace acft { 14 | 15 | // CLASS AERO 16 | // ========== 17 | // ========== 18 | 19 | class ACFT_API aero { 20 | protected: 21 | /**< wing surface */ 22 | double _S_m2; 23 | /**< wing chord */ 24 | double _c_m; 25 | /**< wing span */ 26 | double _b_m; 27 | /**< convenience coefficients */ 28 | Eigen::Array3d _bc; 29 | /**< center of gravity position */ 30 | Eigen::Array3d _xcg_m; 31 | 32 | public: 33 | /**< empty constructor */ 34 | aero() = default; 35 | /**< copy constructor */ 36 | aero(const aero&) = delete; 37 | /**< move constructor */ 38 | aero(aero&&) = delete; 39 | /**< destructor */ 40 | virtual ~aero() = default; 41 | /**< copy assignment */ 42 | aero& operator=(const aero&) = delete; 43 | /**< move assignment */ 44 | aero& operator=(aero&&) = delete; 45 | 46 | /**< computes the aerodynamic forces coefficient based on the true airspeed, the Euler angles 47 | from WFS to BFS (angles of attack and sideslip), the control parameters, and the angular 48 | velocity of BFS over NED expressed in BFS. */ 49 | virtual Eigen::Vector3d obtain_cf_aer(const double& vtas_mps, const ang::euler& euler_wfsbfs_rad, const Eigen::Array4d& delta_control, const Eigen::Vector3d& w_nedbfsbfs_rps) const = 0; 50 | /**< converts aerodynamic force coefficcient into aerodynamic force */ 51 | virtual Eigen::Vector3d cfaer2faer(const Eigen::Vector3d& cf_aer_bfs, const double& rho_kgm3, const double& vtas_mps) const 52 | {return cf_aer_bfs * .5 * rho_kgm3 * _S_m2 * pow(vtas_mps, 2);} 53 | /**< computes the aerodynamics moments coefficient based on the true airspeed, the Euler angles 54 | from WFS to BFS (angles of attack and sideslip), the control parameters, and the angular 55 | velocity of BFS over NED expressed in BFS. */ 56 | virtual Eigen::Vector3d obtain_cm_aer(const double& vtas_mps, const ang::euler& euler_wfsbfs_rad, const Eigen::Array4d& delta_control, const Eigen::Vector3d& w_nedbfsbfs_rps) const = 0; 57 | /**< converts aerodynamic moment coefficient into aerodynamic moment */ 58 | virtual Eigen::Vector3d cmaer2maer(const Eigen::Vector3d& cm_aer_bfs, const double& rho_kgm3, const double& vtas_mps) const 59 | {return (cm_aer_bfs.array() * _bc).matrix() * rho_kgm3 * _S_m2 * pow(vtas_mps,2);} 60 | }; // closes class aero3 61 | 62 | //////////////////////////////////////////////////////////////////////////////////// 63 | //////////////////////////////////////////////////////////////////////////////////// 64 | 65 | } // closes namespace acft 66 | 67 | #endif 68 | 69 | -------------------------------------------------------------------------------- /project_phd/phd/acft/control/logic.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_CONTROL_LOGIC 2 | #define ACFT_CONTROL_LOGIC 3 | 4 | #include "../acft.h" 5 | 6 | namespace control { 7 | namespace logic { 8 | /**< enumeration that contains the different controls */ 9 | enum CNTR_ID { 10 | cntr_THR = 0, 11 | cntr_ELV = 1, 12 | cntr_AIL = 2, 13 | cntr_RUD = 3, 14 | cntr_id_size = 4 15 | }; 16 | /**< Enumeration that contains the different throttle guidance modes */ 17 | enum THR_ID { 18 | thr_vtas_mps = 0, 19 | thr_deltaT = 1, 20 | thr_id_size = 2 21 | }; 22 | /**< Enumeration that contains the different elevator guidance modes */ 23 | enum ELV_ID { 24 | elv_theta_deg = 0, 25 | elv_Hp_m = 1, 26 | elv_h_m = 2, 27 | elv_gammaTAS_deg = 3, 28 | elv_id_size = 4 29 | }; 30 | /**< Enumeration that contains the different ailerons guidance modes */ 31 | enum AIL_ID { 32 | ail_xi_deg = 0, 33 | ail_chi_deg = 1, 34 | ail_psi_deg = 2, 35 | ail_muTAS_deg = 3, 36 | ail_chiTAS_deg = 4, 37 | ail_id_size = 5 38 | }; 39 | /**< Enumeration that contains the different rudder guidance modes */ 40 | enum RUD_ID { 41 | rud_beta_deg = 0, 42 | rud_id_size = 1 43 | }; 44 | /**< Enumeration that contains the different trigger guidance modes 45 | * (use trgg instead of trg so name does not coincide with trigger classes) */ 46 | enum TRG_ID { 47 | trgg_t_sec = 0, 48 | trgg_Deltat_sec = 1, 49 | trgg_h_m = 2, 50 | trgg_Hp_m = 3, 51 | trgg_gamma_deg = 4, 52 | trgg_chi_deg = 5, 53 | trgg_psi_deg = 6, 54 | trgg_id_size = 7 55 | }; 56 | /**< enumeration that contains the different primary PID control loops */ 57 | enum PID_PRIM_ID { 58 | pid_THR_vtas_mps = 0, 59 | pid_ELV_theta_deg = 1, 60 | pid_AIL_xi_deg = 2, 61 | pid_RUD_beta_deg = 3, 62 | pid_prim_id_size = 4 63 | }; 64 | /**< enumeration that contains the different secondary PID control loops */ 65 | enum PID_SECND_ID { 66 | pid_ELV_Hp_m = 0, 67 | pid_ELV_h_m = 1, 68 | pid_ELV_gammaTAS_deg = 2, 69 | pid_AIL_chi_deg = 3, 70 | pid_AIL_psi_deg = 4, 71 | pid_AIL_muTAS_deg = 5, 72 | pid_AIL_chiTAS_deg = 6, 73 | pid_secnd_id_size = 7 74 | }; 75 | 76 | } // closes namespace logic 77 | } // closes namespace control 78 | 79 | #endif 80 | -------------------------------------------------------------------------------- /project_phd/phd/acft/control/pid_factory.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_PID_FACTORY 2 | #define ACFT_PID_FACTORY 3 | 4 | #include "../acft.h" 5 | #include "pid_secnd.h" 6 | 7 | namespace control { 8 | 9 | // CLASS PID FACTORY 10 | // ================= 11 | // ================= 12 | 13 | class ACFT_API pid_factory { 14 | public: 15 | /**< returns pointer to primary_pid control loop based on input enumeration and control period */ 16 | static control::pid_prim* create_pid_prim(const control::logic::PID_PRIM_ID& id, const double& Deltat_sec_cntr); 17 | /**< returns pointer to secondary_pid control loop based on input enumeration, primary control PID, and control period */ 18 | static control::pid_secnd* create_pid_secnd(const control::logic::PID_SECND_ID& id, control::pid_prim& Opid_prim, const double& Deltat_sec_cntr); 19 | 20 | /**< returns multiple for primary throttle control set point ramp low pass filter */ 21 | static double obtain_thr_low_pass_ramp_prim_multiple(const control::logic::THR_ID& thr_id); 22 | /**< returns multiple for primary elevator control set point ramp low pass filter */ 23 | static double obtain_elv_low_pass_ramp_prim_multiple(const control::logic::ELV_ID& elv_id); 24 | /**< returns multiple for primary ailerons control set point ramp low pass filter */ 25 | static double obtain_ail_low_pass_ramp_prim_multiple(const control::logic::AIL_ID& ail_id); 26 | /**< returns multiple for primary rudder control set point ramp low pass filter */ 27 | static double obtain_rud_low_pass_ramp_prim_multiple(const control::logic::RUD_ID& rud_id); 28 | }; // closes class pid_factory 29 | 30 | ////////////////////////////////////////////////////////////////////////////// 31 | ////////////////////////////////////////////////////////////////////////////// 32 | 33 | } // closes namespace control 34 | 35 | #endif 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /project_phd/phd/acft/control/pid_mimo.cpp: -------------------------------------------------------------------------------- 1 | #include "pid_mimo.h" 2 | #include "../guid/guid.h" 3 | //#include 4 | 5 | ////////////////////////////////////////////////////////////////////////////// 6 | ////////////////////////////////////////////////////////////////////////////// 7 | 8 | // CLASS PID_MIMO 9 | // ============== 10 | // ============== 11 | 12 | void control::pid_mimo::fill_target(st::st_cntr& Ost_cntr, const control::guid_op& Oguid_op, control::logic::CNTR_ID cntr_id, const st::st_cntr& Ost_cntr_prev) const { 13 | //Ost_cntr.get_target()[cntr_id] = Oguid_op.get_guid_val(cntr_id); 14 | Ost_cntr.get_target()[cntr_id] = _Plpf_ramp->eval(Oguid_op.get_guid_val(cntr_id)); 15 | } 16 | /* fill up main target (either primary or secondary) */ 17 | 18 | void control::pid_mimo::fill_pid(st::st_cntr& Ost_cntr, control::logic::CNTR_ID cntr_id, const st::st_nav_out& Ost_nav_out, const st::st_cntr& Ost_cntr_prev) const { 19 | Ost_cntr.get_err()[cntr_id] = Ost_cntr.get_target()[cntr_id] - _Ppid_functor->eval(Ost_nav_out); 20 | Ost_cntr.get_err_lpf()[cntr_id] = _Plpf_der->eval(Ost_cntr.get_err()[cntr_id]); 21 | Ost_cntr.get_accum()[cntr_id] = Ost_cntr_prev.get_accum()[cntr_id] + Ost_cntr.get_err()[cntr_id]; 22 | Ost_cntr.get_Delta()[cntr_id] = Ost_cntr.get_err_lpf()[cntr_id] - Ost_cntr_prev.get_err_lpf()[cntr_id]; 23 | // differential error computed based on low pass error, not original error} 24 | } 25 | /* fill up error, accumulated error, differential error, and low pass error (if applicable) */ 26 | 27 | double control::pid_mimo::eval(const st::st_cntr& Ost_cntr, control::logic::CNTR_ID cntr_id, const st::st_nav_out& Ost_nav_out) const { 28 | double delta = _delta_eq + _Kp * Ost_cntr.get_err()[cntr_id] + _Ki * Ost_cntr.get_accum()[cntr_id] + _Kd * Ost_cntr.get_Delta()[cntr_id]; 29 | //double deltaerr = _Kp * Ost_cntr.get_err()[_cntr_id]; 30 | //double deltaacu = _Ki * Ost_cntr.get_accum()[_cntr_id]; 31 | //double deltaDel = _Kd * Ost_cntr.get_Delta()[_cntr_id]; 32 | double delta_mimo = _Ppid_mimo->eval(Ost_cntr, Ost_nav_out); 33 | // the line above works because the fill_pid methods of all four pid controllers have been called before, computing err, accum, and Delta 34 | //std::cout << "XXXXXXXXXXXXXX " << delta << " " << delta_mimo << std::endl; 35 | delta = delta + delta_mimo; 36 | return std::max(std::min(delta + delta_mimo, _max), _min); 37 | } 38 | /* evaluates PID response, returning the desired position of the control parameter */ 39 | 40 | ////////////////////////////////////////////////////////////////////////////// 41 | ////////////////////////////////////////////////////////////////////////////// 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | -------------------------------------------------------------------------------- /project_phd/phd/acft/control/pid_p.cpp: -------------------------------------------------------------------------------- 1 | #include "pid_p.h" 2 | #include "../guid/guid.h" 3 | 4 | ////////////////////////////////////////////////////////////////////////////// 5 | ////////////////////////////////////////////////////////////////////////////// 6 | 7 | // CLASS PID_P_PRIM 8 | // ================ 9 | // ================ 10 | 11 | double control::pid_p_prim::eval(const st::st_cntr& Ost_cntr, const st::st_nav_out& Ost_nav_out) const { 12 | double delta = _delta_eq + _Kp * (Ost_cntr.get_target()[_cntr_id] - _Ppid_functor->eval(Ost_nav_out)); 13 | return std::max(std::min(delta, _max), _min); 14 | } 15 | /* evaluates control loop response */ 16 | 17 | ////////////////////////////////////////////////////////////////////////////// 18 | ////////////////////////////////////////////////////////////////////////////// 19 | 20 | // CLASS PID_P_CONST 21 | // ================= 22 | // ================= 23 | 24 | double control::pid_p_const::eval(const st::st_cntr& Ost_cntr, const st::st_nav_out& Ost_nav_out) const { 25 | double delta = _delta_eq + _Kp * (_target - _Ppid_functor->eval(Ost_nav_out)); 26 | return std::max(std::min(delta, _max), _min); 27 | } 28 | /* evaluates control loop response */ 29 | 30 | ////////////////////////////////////////////////////////////////////////////// 31 | ////////////////////////////////////////////////////////////////////////////// 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | -------------------------------------------------------------------------------- /project_phd/phd/acft/control/pid_prim.cpp: -------------------------------------------------------------------------------- 1 | #include "pid_prim.h" 2 | #include "../guid/guid.h" 3 | //#include 4 | 5 | ////////////////////////////////////////////////////////////////////////////// 6 | ////////////////////////////////////////////////////////////////////////////// 7 | 8 | // CLASS PID_PRIMARY 9 | // ================= 10 | // ================= 11 | 12 | void control::pid_prim::fill_target(st::st_cntr& Ost_cntr, const control::guid_op& Oguid_op, control::logic::CNTR_ID cntr_id, const st::st_cntr& Ost_cntr_prev) const { 13 | //Ost_cntr.get_target()[cntr_id] = Oguid_op.get_guid_val(cntr_id); 14 | Ost_cntr.get_target()[cntr_id] = _Plpf_ramp->eval(Oguid_op.get_guid_val(cntr_id)); 15 | } 16 | /* fill up main target (either primary or secondary) */ 17 | 18 | void control::pid_prim::fill_pid(st::st_cntr& Ost_cntr, control::logic::CNTR_ID cntr_id, const st::st_nav_out& Ost_nav_out, const st::st_cntr& Ost_cntr_prev) const { 19 | Ost_cntr.get_err()[cntr_id] = Ost_cntr.get_target()[cntr_id] - _Ppid_functor->eval(Ost_nav_out); 20 | Ost_cntr.get_err_lpf()[cntr_id] = _Plpf_der->eval(Ost_cntr.get_err()[cntr_id]); 21 | Ost_cntr.get_accum()[cntr_id] = Ost_cntr_prev.get_accum()[cntr_id] + Ost_cntr.get_err()[cntr_id]; 22 | Ost_cntr.get_Delta()[cntr_id] = Ost_cntr.get_err_lpf()[cntr_id] - Ost_cntr_prev.get_err_lpf()[cntr_id]; 23 | // differential error computed based on low pass error, not original error 24 | } 25 | /* fill up error, accumulated error, differential error, and low pass error (if applicable) */ 26 | 27 | double control::pid_prim::eval(const st::st_cntr& Ost_cntr, control::logic::CNTR_ID cntr_id, const st::st_nav_out& Ost_nav_out) const { 28 | double delta = _delta_eq + _Kp * Ost_cntr.get_err()[cntr_id] + _Ki * Ost_cntr.get_accum()[cntr_id] + _Kd * Ost_cntr.get_Delta()[cntr_id]; 29 | //double deltaerr = _Kp * Ost_cntr.get_err()[_cntr_id]; 30 | //double deltaacu = _Ki * Ost_cntr.get_accum()[_cntr_id]; 31 | //double deltaDel = _Kd * Ost_cntr.get_Delta()[_cntr_id]; 32 | return std::max(std::min(delta, _max), _min); 33 | } 34 | /* evaluates PID response, returning the desired position of the control parameter */ 35 | 36 | ////////////////////////////////////////////////////////////////////////////// 37 | ////////////////////////////////////////////////////////////////////////////// 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /project_phd/phd/acft/sens/camera.cpp: -------------------------------------------------------------------------------- 1 | #include "camera.h" 2 | #include "math/templates/math_.h" 3 | 4 | // CLASS CAMERA 5 | // ============ 6 | // ============ 7 | 8 | /////////////////////////////////////////////////////// 9 | // LLAMARLO ASÏ: 10 | // auto Pcam = new sens::camera(768, 1024, 49.2255, euler_bc); //focal length of 19 [mm] equals vfov of 49.2255 [deg] 11 | ////////////////////////////////////////////////////// 12 | 13 | sens::camera::camera(const unsigned int& width_px, const unsigned int& height_px, const double& vfov_deg, const ang::euler& euler_bc) 14 | : _width_px(width_px), _height_px(height_px), _vfov_deg(vfov_deg), _f_px(height_px / (2.0 * tan(0.5 * vfov_deg * math::constant::D2R()))), 15 | _cx_px(0.5 * width_px - 0.5), _cy_px(0.5 * height_px - 0.5), _euler_bc(euler_bc), _R_bc(euler_bc), _q_bc(euler_bc) { 16 | } 17 | /* constructor based on images width and height, vertical field of view, and Euler angles from body to camera */ 18 | 19 | Eigen::Vector3d sens::camera::convert_img2uscrs(const Eigen::Vector2d& x_img_px) const { 20 | return this->convert_img2uscrs(x_img_px[0], x_img_px[1]); 21 | } 22 | /* projection from pixels to world coordiantes, returning unitary bearing vector */ 23 | 24 | Eigen::Vector3d sens::camera::convert_img2uscrs(const double& x_img_pxi, const double& x_img_pxii) const { 25 | Eigen::Vector3d xyz; 26 | xyz[0] = (x_img_pxi - _cx_px) / _f_px; 27 | xyz[1] = (x_img_pxii - _cy_px) / _f_px; 28 | xyz[2] = 1.0; 29 | return xyz.normalized(); 30 | } 31 | /* projection from pixels to world coordiantes, returning unitary bearing vector */ 32 | 33 | Eigen::Vector2d sens::camera::convert_crs2img(const Eigen::Vector3d& x_crs_m) const { 34 | return this->convert_upcrs2img(Eigen::Vector2d(x_crs_m(0)/x_crs_m(2), x_crs_m(1)/x_crs_m(2))); 35 | } 36 | /* transforms cartesian coordinates from camera reference system (CRS) to image reference system (IMG). 37 | Unit sphere or unit plane camera reference systems (USCRS or UPCRS) are also acceptable inputs. */ 38 | 39 | Eigen::Vector2d sens::camera::convert_upcrs2img(const Eigen::Vector2d& x_crs_up) const { 40 | return Eigen::Vector2d(_f_px * x_crs_up(0) + _cx_px, _f_px * x_crs_up(1) + _cy_px); 41 | } 42 | /* transforms cartesian coordinates from unit plane (3rd coord == 1) camera reference system (UPCRS) to image reference system (IMG) */ 43 | 44 | bool sens::camera::is_in_frame(const Eigen::Vector2i& x_car_img_px, int boundary) const { 45 | if ((x_car_img_px[0] >= boundary) && (x_car_img_px[0] < _width_px-boundary) && 46 | (x_car_img_px[1] >= boundary) && (x_car_img_px[1] < _height_px-boundary)) { 47 | return true; 48 | } 49 | return false; 50 | } 51 | /* returns true if input image reference system (IMG) coordinates are inside frame and not closer than input boundary to frame border */ 52 | 53 | bool sens::camera::is_in_frame(const Eigen::Vector2i& x_car_img_px, int boundary, int level) const { 54 | if ((x_car_img_px[0] >= boundary) && (x_car_img_px[0] < _width_px / math::pyramid_scale(level) - boundary) && 55 | (x_car_img_px[1] >= boundary) && (x_car_img_px[1] < _height_px / math::pyramid_scale(level) - boundary)) { 56 | return true; 57 | } 58 | return false; 59 | } 60 | /* returns true if input image reference system (IMG) coordinates (at input pyramid level) are inside frame and not closer than input boundary to frame border */ 61 | 62 | 63 | 64 | 65 | 66 | -------------------------------------------------------------------------------- /project_phd/phd/acft/sens/sens_single_no_walk.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_SENS_SINGLE_NO_WALK 2 | #define ACFT_SENS_SINGLE_NO_WALK 3 | 4 | #include "../acft.h" 5 | #include "logic.h" 6 | #include "env/coord.h" 7 | 8 | #include 9 | #include 10 | #include 11 | 12 | namespace sens { 13 | 14 | // CLASS SENS_SINGLE_NO_WALK 15 | // ========================= 16 | // ========================= 17 | 18 | class ACFT_API sens_single_no_walk { 19 | private: 20 | /**< white noise [unit] */ 21 | double _sigma; 22 | /**< bias offset [unit] */ 23 | double _B0; 24 | /**< time interval between measurements [sec] */ 25 | double _Deltat_sec; 26 | 27 | /**< seed generator */ 28 | std::ranlux24_base _gen; 29 | /**< standard normal distribution */ 30 | std::normal_distribution _dist; 31 | 32 | /**< _B0 * Nu0 */ 33 | double _B0Nu0; 34 | public: 35 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 36 | 37 | /**< default constructor */ 38 | sens_single_no_walk() = delete; 39 | /**< constructor based on white noise, bias offset, time interval between maesurements, and seed */ 40 | sens_single_no_walk(const double& sigma, const double& B0, const double& Deltat_sec, const int& seed); 41 | /**< copy constructor */ 42 | sens_single_no_walk(const sens_single_no_walk&) = delete; 43 | /**< move constructor */ 44 | sens_single_no_walk(sens_single_no_walk&&) = delete; 45 | /**< destructor */ 46 | ~sens_single_no_walk() = default; 47 | /**< copy assignment */ 48 | sens_single_no_walk& operator=(const sens_single_no_walk&) = delete; 49 | /**< move assignment */ 50 | sens_single_no_walk& operator=(sens_single_no_walk&&) = delete; 51 | 52 | /**< return new sensor measurement based on sensor input, also filling up the input bias */ 53 | double eval(const double& Oinput, double& Obias); 54 | 55 | /**< create true airspeed sensor model */ 56 | static sens::sens_single_no_walk* create_tas_sensor(sens::logic::TAS_ID, const int& seed, const double& Deltat_sec); 57 | /**< create angle of attack sensor model */ 58 | static sens::sens_single_no_walk* create_aoa_sensor(sens::logic::AOA_ID, const int& seed, const double& Deltat_sec); 59 | /**< create angle of sideslip sensor model */ 60 | static sens::sens_single_no_walk* create_aos_sensor(sens::logic::AOS_ID, const int& seed, const double& Deltat_sec); 61 | /**< create outside static pressure sensor model */ 62 | static sens::sens_single_no_walk* create_osp_sensor(sens::logic::OSP_ID, const int& seed, const double& Deltat_sec); 63 | /**< create outside air temperature sensor model */ 64 | static sens::sens_single_no_walk* create_oat_sensor(sens::logic::OAT_ID, const int& seed, const double& Deltat_sec); 65 | 66 | /**< get white noise [unit] to read */ 67 | const double& get_sigma() const {return _sigma;} 68 | /**< get bias offset [unit] to read */ 69 | const double& get_B0() const {return _B0;} 70 | /**< get bias offset [unit] realization to read */ 71 | const double& get_B0Nu0() const {return _B0Nu0;} 72 | /**< get time interval between measurements [sec] to read */ 73 | const double& get_Deltat_sec() const {return _Deltat_sec;} 74 | }; // closes class sens_single_no_walk 75 | 76 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 77 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 78 | 79 | }; // closes namespace sens 80 | 81 | #endif 82 | -------------------------------------------------------------------------------- /project_phd/phd/acft/sens/sens_single_noise.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_SENS_SINGLE_NOISE 2 | #define ACFT_SENS_SINGLE_NOISE 3 | 4 | #include "../acft.h" 5 | #include "logic.h" 6 | #include "env/coord.h" 7 | 8 | #include 9 | #include 10 | #include 11 | 12 | namespace sens { 13 | 14 | // CLASS SENS_SINGLE_NOISE 15 | // ======================= 16 | // ======================= 17 | 18 | class ACFT_API sens_single_noise { 19 | private: 20 | /**< white noise [unit] */ 21 | double _sigma; 22 | /**< time interval between measurements [sec] */ 23 | double _Deltat_sec; 24 | 25 | /**< seed generator */ 26 | std::ranlux24_base _gen; 27 | /**< standard normal distribution */ 28 | std::normal_distribution _dist; 29 | public: 30 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 31 | 32 | /**< default constructor */ 33 | sens_single_noise() = delete; 34 | /**< constructor based on white noise, time interval between measurements, and seed */ 35 | sens_single_noise(const double& sigma_v, const double& Deltat_sec, const int& seed); 36 | /**< copy constructor */ 37 | sens_single_noise(const sens_single_noise&) = delete; 38 | /**< move constructor */ 39 | sens_single_noise(sens_single_noise&&) = delete; 40 | /**< destructor */ 41 | ~sens_single_noise() = default; 42 | /**< copy assignment */ 43 | sens_single_noise& operator=(const sens_single_noise&) = delete; 44 | /**< move assignment */ 45 | sens_single_noise& operator=(sens_single_noise&&) = delete; 46 | 47 | /**< return new sensor measurement */ 48 | double eval(const double& Oinput); 49 | 50 | /**< create outside static pressure sensor model */ 51 | //static sens::sens_single_noise* create_osp_sensor(sens::logic::OSP_ID, const int& seed, const double& Deltat_sec); 52 | /**< create outside air temperature sensor model */ 53 | //static sens::sens_single_noise* create_oat_sensor(sens::logic::OAT_ID, const int& seed, const double& Deltat_sec); 54 | /**< create true airspeed sensor model */ 55 | //static sens::sens_single_noise* create_tas_sensor(sens::logic::TAS_ID, const int& seed, const double& Deltat_sec); 56 | 57 | /**< get white noise [unit] to read */ 58 | const double& get_sigma() const {return _sigma;} 59 | /**< get time interval between measurements [sec] to read */ 60 | const double& get_Deltat_sec() const {return _Deltat_sec;} 61 | }; // closes class sens_single_noise 62 | 63 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 64 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 65 | 66 | }; // closes namespace sens 67 | 68 | #endif 69 | -------------------------------------------------------------------------------- /project_phd/phd/acft/sens/sens_single_one_use.cpp: -------------------------------------------------------------------------------- 1 | #include "sens_single_one_use.h" 2 | 3 | #include 4 | 5 | // CLASS SENS_SINGLE_ONE_USE 6 | // =========================== 7 | // =========================== 8 | 9 | sens::sens_single_one_use::sens_single_one_use(const double& sigma, const int& seed) 10 | : _sigma(sigma), _gen(seed), _dist(0.,1.) { 11 | //std::cout << seed << std::endl; 12 | } 13 | /* constructor based on white noise and seed */ 14 | 15 | double sens::sens_single_one_use::eval() { 16 | return _sigma * _dist(_gen); 17 | } 18 | /* return new sensor measurement */ 19 | 20 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 21 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /project_phd/phd/acft/sens/sens_single_one_use.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_SENS_SINGLE_ONE_USE 2 | #define ACFT_SENS_SINGLE_ONE_USE 3 | 4 | #include "../acft.h" 5 | #include "logic.h" 6 | #include "env/coord.h" 7 | 8 | #include 9 | #include 10 | #include 11 | 12 | namespace sens { 13 | 14 | // CLASS SENS_SINGLE_ONE_USE 15 | // =========================== 16 | // =========================== 17 | 18 | class ACFT_API sens_single_one_use { 19 | private: 20 | /**< white noise [unit] */ 21 | double _sigma; 22 | /**< seed generator */ 23 | std::ranlux24_base _gen; 24 | /**< standard normal distribution */ 25 | std::normal_distribution _dist; 26 | public: 27 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 28 | 29 | /**< default constructor */ 30 | sens_single_one_use() = delete; 31 | /**< constructor based on white noise and seed */ 32 | sens_single_one_use(const double& sigma, const int& seed); 33 | /**< copy constructor */ 34 | sens_single_one_use(const sens_single_one_use&) = delete; 35 | /**< move constructor */ 36 | sens_single_one_use(sens_single_one_use&&) = delete; 37 | /**< destructor */ 38 | ~sens_single_one_use() = default; 39 | /**< copy assignment */ 40 | sens_single_one_use& operator=(const sens_single_one_use&) = delete; 41 | /**< move assignment */ 42 | sens_single_one_use& operator=(sens_single_one_use&&) = delete; 43 | 44 | /**< return new sensor measurement */ 45 | double eval(); 46 | 47 | /**< get white noise [unit] to read */ 48 | const double& get_sigma() const {return _sigma;} 49 | }; // closes class sens_single_one_use 50 | 51 | }; // closes namespace sens 52 | 53 | #endif 54 | -------------------------------------------------------------------------------- /project_phd/phd/acft/sens/suite.cpp: -------------------------------------------------------------------------------- 1 | #include "suite.h" 2 | 3 | #include "math/logic/share.h" 4 | #include "ang/rotate/rodrigues.h" 5 | #include "acft/acft/iner.h" 6 | #include 7 | #include 8 | 9 | // CLASS SUITE 10 | // =========== 11 | // =========== 12 | 13 | sens::suite::suite(math::seeder& Oseeder, 14 | sens::logic::ACC_ID acc_id, sens::logic::GYR_ID gyr_id, sens::logic::MAG_ID mag_id, 15 | sens::logic::OSP_ID osp_id, sens::logic::OAT_ID oat_id, sens::logic::TAS_ID tas_id, 16 | sens::logic::AOA_ID aoa_id, sens::logic::AOS_ID aos_id, sens::logic::GPS_ID gps_id, 17 | sens::logic::BAND_ID band_id, 18 | const double& Deltat_sec_sens, bool flag_console) 19 | : _acc_id(acc_id), _gyr_id(gyr_id), 20 | _Pacc(nullptr), _Pgyr(nullptr), _Pmag(nullptr), _Posp(nullptr), _Poat(nullptr), _Ptas(nullptr), _Paoa(nullptr), _Paos(nullptr), _Pgps(nullptr), _Pplat(nullptr) { 21 | 22 | // fill up individual sensor pointers 23 | _Pplat = sens::platform::create_platform(Oseeder.provide_seed(math::seeder::seeder_acft_plat), flag_console); 24 | _Pacc = sens::sens_triple_acc::create_accelerometer(acc_id, band_id, Oseeder.provide_seed(math::seeder::seeder_acft_acc), Oseeder.provide_seed(math::seeder::seeder_acc), *_Pplat, Deltat_sec_sens); 25 | _Pgyr = sens::sens_triple_gyr::create_gyroscope(gyr_id, band_id, Oseeder.provide_seed(math::seeder::seeder_acft_gyr), Oseeder.provide_seed(math::seeder::seeder_gyr), *_Pplat, Deltat_sec_sens); 26 | _Pmag = sens::sens_triple_mag::create_magnetometer(mag_id, Oseeder.provide_seed(math::seeder::seeder_acft_mag), Oseeder.provide_seed(math::seeder::seeder_mag), Oseeder.get_seed_order(), Deltat_sec_sens); 27 | _Posp = sens::sens_single_no_walk::create_osp_sensor(osp_id, Oseeder.provide_seed(math::seeder::seeder_osp), Deltat_sec_sens); 28 | _Ptas = sens::sens_single_no_walk::create_tas_sensor(tas_id, Oseeder.provide_seed(math::seeder::seeder_tas), Deltat_sec_sens); 29 | _Paoa = sens::sens_single_no_walk::create_aoa_sensor(aoa_id, Oseeder.provide_seed(math::seeder::seeder_aoa), Deltat_sec_sens); 30 | _Paos = sens::sens_single_no_walk::create_aos_sensor(aos_id, Oseeder.provide_seed(math::seeder::seeder_aos), Deltat_sec_sens); 31 | _Poat = sens::sens_single_no_walk::create_oat_sensor(oat_id, Oseeder.provide_seed(math::seeder::seeder_oat), Deltat_sec_sens); 32 | _Pgps = sens::sens_triple_gps::create_gps_sensor(gps_id, Oseeder.provide_seed(math::seeder::seeder_gps)); 33 | } 34 | /* constructor based on seed order, specific accelerometer, gyroscope, magnetometer, pressure, temperature, airspeed, angle of attack, angle of sideslip. Flag true to show platform summary in console. */ 35 | 36 | sens::suite::~suite() { 37 | delete _Pacc; 38 | delete _Pgyr; 39 | delete _Pmag; 40 | delete _Posp; 41 | delete _Poat; 42 | delete _Ptas; 43 | delete _Paoa; 44 | delete _Paos; 45 | delete _Pgps; 46 | delete _Pplat; 47 | } 48 | /* destructor */ 49 | 50 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 51 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname acft_test) 3 | 4 | file (GLOB dir_27_headers *.h *.hpp) 5 | source_group("" FILES ${dir_27_headers}) 6 | set(all_headers ${dir_27_headers} ) 7 | 8 | file (GLOB dir_28_sources *.cpp *.c) 9 | source_group("" FILES ${dir_28_sources}) 10 | set(all_sources ${dir_28_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DATTITUDE_DLL) 21 | add_definitions(-DEARTH_DLL) 22 | add_definitions(-DFDYN_DLL) 23 | add_definitions(-DJAIL_DLL) 24 | # End Windows compatibility 25 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 26 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 27 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 28 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 29 | target_link_libraries(${prjname} debug jail${DEBUG_TARGET_SUFFIX} optimized jail) 30 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 31 | 32 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 33 | target_link_libraries(${prjname} optimized ${A_LIB}) 34 | endforeach() 35 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 36 | target_link_libraries(${prjname} debug ${A_LIB}) 37 | endforeach() 38 | 39 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/Tapm.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_TEST_APM 2 | #define ACFT_TEST_APM 3 | 4 | #include "acft_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | namespace acft { 8 | namespace test { 9 | 10 | class Tapm: public ::jail::unit_test { 11 | public: 12 | /**< constructor based on counter */ 13 | explicit Tapm(jail::counter&); 14 | /**< execute tests and write results on console */ 15 | void run() override; 16 | /**< specific tests */ 17 | 18 | void test_aero0(); // comparison of aero0 with matlab results 19 | void test_aero1(); // comparison of aero1 with matlab results 20 | void test_aero2(); // comparison of aero2 with matlab results 21 | void test_aero3(); // comparison of aero3 with matlab results 22 | void test_prop(); // comparison of propulsion with matlab results 23 | void test_iner(); 24 | 25 | }; 26 | 27 | } // closes namespace test 28 | 29 | } // closes namespace acft 30 | 31 | #endif 32 | 33 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/Tapm_plots.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_TEST_APM_PLOTS 2 | #define ACFT_TEST_APM_PLOTS 3 | 4 | #include "acft_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | /* 8 | This file contains tests to generate the PhD APM plots. 9 | */ 10 | 11 | namespace acft { 12 | namespace test { 13 | 14 | class Tapm_plots: public ::jail::unit_test { 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tapm_plots(jail::counter&); 18 | /**< execute tests and write results on console */ 19 | void run() override; 20 | /**< specific tests */ 21 | 22 | void test1_cl_cd_cmm_alpha__deltaE(); 23 | void test2_cl_cd_cmm_alpha__beta(); 24 | void test3_cy_cml_cmn_beta__deltaR(); 25 | void test4_cy_cml_cmn_beta__deltaA(); 26 | void test5_cmn_alpha__deltaR(); 27 | void test6_cml_alpha__deltaA(); 28 | void test7_P_F_Hp__deltaT(); 29 | void test8_ct_cp_eta__J(); 30 | void test9_n_T_M_P__vtas(); 31 | 32 | }; 33 | 34 | } // closes namespace test 35 | 36 | } // closes namespace acft 37 | 38 | #endif 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/Tbrick.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_TEST_BRICK 2 | #define ACFT_TEST_BRICK 3 | 4 | #include "acft_test.h" 5 | #include "env/geo.h" 6 | #include "ang/quat.h" 7 | 8 | #include "jail/unit_test.h" 9 | 10 | namespace acft { 11 | namespace test { 12 | 13 | class brick_motion { 14 | private: 15 | static void aux(const double& t_sec, 16 | env::geodetic_coord& dx_gdt_rad_m, 17 | Eigen::Vector3d& dv_bfs_mps_dt, 18 | ang::quat& dq_nedbfs_dt, 19 | Eigen::Vector3d& dh_bfsirsbfs_Nms_dt, 20 | const env::geodetic_coord& x_gdt_rad_m, 21 | const Eigen::Vector3d& v_bfs_mps, 22 | const ang::rodrigues& q_nedbfs, 23 | const Eigen::Vector3d& h_bfsirsbfs_Nms, 24 | const env::geo& Ogeo, 25 | const Eigen::Matrix3d& I_kgm2); 26 | public: 27 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 28 | /**< integrates the motion of a brick for the input time */ 29 | static std::vector solve(double t_sec_end); 30 | 31 | }; // closes class brick_motion 32 | 33 | //////////////////////////////////////////////////////////////////////////////////////////// 34 | //////////////////////////////////////////////////////////////////////////////////////////// 35 | 36 | class Tbrick: public ::jail::unit_test { 37 | public: 38 | /**< constructor based on counter */ 39 | explicit Tbrick(jail::counter&); 40 | /**< execute tests and write results on console */ 41 | void run() override; 42 | /**< specific tests */ 43 | void test_brick_motion(); 44 | 45 | }; 46 | 47 | } // closes namespace test 48 | 49 | } // closes namespace acft 50 | #endif 51 | 52 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/Tsensor.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_TEST_SENSOR 2 | #define ACFT_TEST_SENSOR 3 | 4 | #include "acft_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | namespace acft { 8 | namespace test { 9 | 10 | class Tsensor: public ::jail::unit_test { 11 | public: 12 | /**< constructor based on counter */ 13 | explicit Tsensor(jail::counter&); 14 | /**< execute tests and write results on console */ 15 | void run() override; 16 | /**< specific tests */ 17 | 18 | void test_single_inertial(); 19 | void test_comparison_gyr_theory(); 20 | void test_comparison_acc_theory(); 21 | ///////////////////////////////////////////////////////////////// 22 | // WATCH OUT -> I NEED TO DEACTIVATE THE BIAS DRIFT LIMITS 23 | ///////////////////////////////////////////////////////////////// 24 | }; 25 | 26 | } // closes namespace test 27 | 28 | } // closes namespace acft 29 | #endif 30 | 31 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/Tsti.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_TEST_STI 2 | #define ACFT_TEST_STI 3 | 4 | #include "acft_test.h" 5 | #include "env/earth.h" 6 | #include "jail/unit_test.h" 7 | 8 | namespace acft { 9 | namespace test { 10 | 11 | class Tsti: public ::jail::unit_test { 12 | public: 13 | /**< constructor based on counter */ 14 | explicit Tsti(jail::counter&); 15 | /**< execute tests and write results on console */ 16 | void run() override; 17 | /**< specific tests */ 18 | 19 | void test1(const double& psi_deg, const env::earth& Oearth); 20 | 21 | }; 22 | 23 | } // closes namespace test 24 | 25 | } // closes namespace acft 26 | 27 | #endif 28 | 29 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/acft_test.h: -------------------------------------------------------------------------------- 1 | #ifndef ACFT_TEST_INCLUDED 2 | #define ACFT_TEST_INCLUDED 3 | 4 | // 4251: some class or template needs to have dll-interface to be used by clients 5 | // of this class. No problem when reffers to templates, clients can link succesfully 6 | // because the class instantiation (the code) is in client side (so no link at all). 7 | // Disabling 4251 can hide a problem when this class (which is dll exported): either 8 | // (1) expose in non-private sections or (2) use in inline functions implementations, 9 | // types witch are not dll exported 10 | // 4996: MSVC has gone into full security-paranoia mode. std::copy issues this warning 11 | // when it is used with raw pointers, because when used incorrectly, it can result in 12 | // buffer overflows. But if code is OK, no problem. Stupid Microsoft warning. 13 | #if defined(_MSC_VER) 14 | # pragma warning(disable:4251) 15 | # pragma warning(disable:4996) 16 | #endif 17 | 18 | // Now we use the generic helper definitions above to define ACFT_TEST_API and ACFT_TEST_LOCAL. 19 | // ACFT_TEST_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 20 | // ACFT_TEST_LOCAL is used for non-api symbols. 21 | 22 | #ifdef ACFT_TEST_DLL // defined if ACFT_TEST is compiled as a DLL 23 | #ifdef ACFT_TEST_DLL_EXPORTS // defined if we are building the ACFT_TEST DLL (instead of using it) 24 | #define ACFT_TEST_API ACFT_HELPER_DLL_EXPORT 25 | #else 26 | #define ACFT_TEST_API ACFT_HELPER_DLL_IMPORT 27 | #endif // ACFT_TEST_DLL_EXPORTS 28 | #define ACFT_TEST_LOCAL ACFT_HELPER_DLL_LOCAL 29 | #else // ACFT_TEST_DLL is not defined: this means ACFT_TEST is a static lib. 30 | #define ACFT_TEST_API 31 | #define ACFT_TEST_LOCAL 32 | #endif // ACFT_TEST_DLL 33 | 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /project_phd/phd/acft_test/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Tapm.h" 3 | #include "Tapm_plots.h" 4 | #include "Tbrick.h" 5 | #include "Tsensor.h" 6 | #include "Tsti.h" 7 | 8 | int main(int argc, char **argv) { 9 | 10 | jail::counter Ocounter; 11 | 12 | {acft::test::Tapm o(Ocounter); o.run(); } 13 | {acft::test::Tapm_plots o(Ocounter); o.run(); } 14 | //{acft::test::Tsensor o(Ocounter); o.run(); } 15 | {acft::test::Tbrick o(Ocounter); o.run(); } 16 | {acft::test::Tsti o(Ocounter); o.run(); } 17 | 18 | Ocounter.write_results(); 19 | 20 | return 0; 21 | } 22 | 23 | 24 | 25 | -------------------------------------------------------------------------------- /project_phd/phd/ang/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname ang) # set cache variable 3 | 4 | file (GLOB dir_0_headers *.h *.hpp) # generates list of files that match expressions and store it into variable 5 | file (GLOB dir_3_headers transform/*.h transform/*.hpp) 6 | file (GLOB dir_4_headers rotate/*.h rotate/*.hpp) 7 | source_group("" FILES ${dir_0_headers}) # define a group into which sources are placed for IDE project generation 8 | source_group("transform" FILES ${dir_3_headers}) 9 | source_group("rotate" FILES ${dir_4_headers}) 10 | set(all_headers ${dir_0_headers} ${dir_3_headers} ${dir_4_headers}) # set cache variable with headers 11 | 12 | file (GLOB dir_0_sources *.cpp *.c) 13 | file (GLOB dir_3_sources transform/*.cpp transform/*.c transform/*.cxx) 14 | file (GLOB dir_4_sources rotate/*.cpp rotate/*.c rotate/*.cxx) 15 | source_group("" FILES ${dir_0_sources}) 16 | source_group("transform" FILES ${dir_3_sources}) 17 | source_group("rotate" FILES ${dir_4_sources}) 18 | set(all_sources ${dir_0_sources} ${dir_3_sources} ${dir_4_sources}) # set cache variable with sources 19 | 20 | string(TOUPPER ${prjname} PRJNAME) # converts prjname to uppercase and loads it into PRJNAME 21 | add_definitions(-D${PRJNAME}_DLL) # adds -D define flags to the compilation of source files 22 | add_definitions(-D${PRJNAME}_DLL_EXPORTS) # adds -D define flags to the compilation of source files 23 | 24 | add_library(${prjname} SHARED ${all_headers} ${all_sources}) # adds library target as SHARED (linked dinamically, shared at runtime) 25 | 26 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) # add target property so debug target has the d suffix 27 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) # add target property so release target coincides with project 28 | 29 | include_directories(${PROJECTS_SRC_ROOT}/phd) # adds input directory to those compiler uses to search for include files. 30 | 31 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 32 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 33 | target_link_libraries(${prjname} optimized ${A_LIB}) # adds all Eigen libraries to target 34 | endforeach() 35 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 36 | target_link_libraries(${prjname} debug ${A_LIB}) # adds all Eigen libraries to target 37 | endforeach() 38 | -------------------------------------------------------------------------------- /project_phd/phd/ang/ang.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Generic helper definitions for shared library support 4 | #if defined _WIN32 || defined __CYGWIN__ 5 | #define ANG_HELPER_DLL_IMPORT __declspec(dllimport) 6 | #define ANG_HELPER_DLL_EXPORT __declspec(dllexport) 7 | #define ANG_HELPER_DLL_LOCAL 8 | #else 9 | #if __GNUC__ >= 4 10 | #define ANG_HELPER_DLL_IMPORT __attribute__ ((visibility ("default"))) 11 | #define ANG_HELPER_DLL_EXPORT __attribute__ ((visibility ("default"))) 12 | #define ANG_HELPER_DLL_LOCAL __attribute__ ((visibility ("hidden"))) 13 | #else 14 | #define ANG_HELPER_DLL_IMPORT 15 | #define ANG_HELPER_DLL_EXPORT 16 | #define ANG_HELPER_DLL_LOCAL 17 | #endif 18 | #endif 19 | 20 | // Now we use the generic helper definitions above to define ANG_API and ANG_LOCAL. 21 | // ANG_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 22 | // ANG_LOCAL is used for non-api symbols. 23 | 24 | #ifdef ANG_DLL // defined if ANG is compiled as a DLL 25 | #ifdef ANG_DLL_EXPORTS // defined if we are building the ANG DLL (instead of using it) 26 | #define ANG_API ANG_HELPER_DLL_EXPORT 27 | #else 28 | #define ANG_API ANG_HELPER_DLL_IMPORT 29 | #endif // ANG_DLL_EXPORTS 30 | #define ANG_LOCAL ANG_HELPER_DLL_LOCAL 31 | #else // ANG_DLL is not defined: this means ANG is a static lib. 32 | #define ANG_API 33 | #define ANG_LOCAL 34 | #endif // ANG_DLL 35 | -------------------------------------------------------------------------------- /project_phd/phd/ang/auxiliary.h: -------------------------------------------------------------------------------- 1 | #ifndef ANG_AUXILIARY 2 | #define ANG_AUXILIARY 3 | 4 | #include "ang.h" 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | // EIGEN EXTENSIONS 12 | // ================ 13 | // ================ 14 | 15 | namespace Eigen { 16 | typedef Matrix< double, 4, 4 > Matrix4d; 17 | typedef Matrix< double, 6, 1 > Vector6d; 18 | typedef Matrix< double, 6, 6 > Matrix6d; 19 | typedef Matrix< double, 9, 1 > Vector9d; 20 | 21 | /**< adds the input 3D Eigen vector object associated rotation vector to the stream */ 22 | ANG_API inline std::ostream& operator <<(std::ostream & out_str, const Eigen::Vector3d& v) { 23 | out_str << v.transpose(); 24 | return out_str; 25 | } 26 | /**< adds the input 4D Eigen vector object to the stream */ 27 | ANG_API inline std::ostream& operator <<(std::ostream & out_str, const Eigen::Vector4d& v) { 28 | out_str << v.transpose(); 29 | return out_str; 30 | } 31 | /**< adds the input 6D Eigen vector object to the stream */ 32 | ANG_API inline std::ostream& operator <<(std::ostream & out_str, const Eigen::Vector6d& v) { 33 | out_str << v.transpose(); 34 | return out_str; 35 | } 36 | 37 | /**< adds the input 3D Eigen matrix object to the stream */ 38 | ANG_API inline std::ostream& operator <<(std::ostream & out_str, const Eigen::Matrix3d& m) { 39 | out_str << m.row(0) << " | " << m.row(1) << " | " << m.row(2); 40 | return out_str; 41 | } 42 | /**< adds the input 4D Eigen matrix object to the stream */ 43 | ANG_API inline std::ostream& operator <<(std::ostream & out_str, const Eigen::Matrix4d& m) { 44 | out_str << m.row(0) << " | " << m.row(1) << " | " << m.row(2) << " | " << m.row(3); 45 | return out_str; 46 | } 47 | } // close namespace Eigen 48 | 49 | /////////////////////////////////////////////////////////////////////////////// 50 | /////////////////////////////////////////////////////////////////////////////// 51 | 52 | #endif 53 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname ang_test) # set cache variable 3 | 4 | file (GLOB dir_8_headers *.h *.hpp) # generates list of files that match expressions and store it into variable 5 | source_group("" FILES ${dir_8_headers}) # define a group into which sources are placed for IDE project generation 6 | set(all_headers ${dir_8_headers}) # set cache variable with headers 7 | 8 | file (GLOB dir_9_sources *.cpp *.c) 9 | SOURCE_GROUP("" FILES ${dir_9_sources}) 10 | set(all_sources ${dir_9_sources}) # set cache variable with sources 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 20 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 21 | target_link_libraries(${prjname} debug jail${DEBUG_TARGET_SUFFIX} optimized jail) 22 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 23 | 24 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 25 | target_link_libraries(${prjname} optimized ${A_LIB}) 26 | endforeach() 27 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 28 | target_link_libraries(${prjname} debug ${A_LIB}) 29 | endforeach() 30 | 31 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/Tcheck.h: -------------------------------------------------------------------------------- 1 | #ifndef ATT_TEST_CHECK 2 | #define ATT_TEST_CHECK 3 | 4 | #include "ang_test.h" 5 | #include 6 | 7 | namespace ang { 8 | namespace test { 9 | 10 | class Tcheck: public ::jail::unit_test { 11 | public: 12 | /**< constructor based on counter */ 13 | explicit Tcheck(jail::counter&); 14 | /**< execute tests and write results on console */ 15 | void run() override; 16 | 17 | /**< specific tests */ 18 | void test1(); 19 | 20 | }; 21 | 22 | } // closes namespace test 23 | } // closes namespace ang 24 | 25 | #endif 26 | 27 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/Tintegration.h: -------------------------------------------------------------------------------- 1 | #ifndef ATT_TEST_INTEGRATION 2 | #define ATT_TEST_INTEGRATION 3 | 4 | #include "ang_test.h" 5 | #include "ang/quat.h" 6 | #include "ang/rotate/rodrigues.h" 7 | #include 8 | #include 9 | #include 10 | 11 | /* 12 | Test of integration of the motion of a rigid body with the different rotation 13 | and transformation methods. 14 | 01 --> space and rodrigues 15 | 02 --> space and dcm 16 | 03 --> space and rotv 17 | 11 --> body and rodrigues 18 | 12 --> body and dcm 19 | 13 --> body and rotv 20 | */ 21 | 22 | namespace ang { 23 | namespace test { 24 | 25 | class Tintegration: public ::jail::unit_test { 26 | public: 27 | /**< constructor based on counter */ 28 | explicit Tintegration(jail::counter&); 29 | /**< execute tests and write results on console */ 30 | void run() override; 31 | 32 | /**< specific tests */ 33 | void test01(std::vector& res, const double& Deltat_sec, const double& t_sec_end, const Eigen::Vector3d& x0_wbw_m, const ang::rodrigues& q0_wb, const Eigen::Vector3d& v0_w_mps, const Eigen::Vector3d& w0_bww_rps, const Eigen::Vector3d& x_bpb_m, const Eigen::Vector3d& a_b_mps2, const Eigen::Vector3d& alpha_b_rps2); 34 | void test02(std::vector& res, const double& Deltat_sec, const double& t_sec_end, const Eigen::Vector3d& x0_wbw_m, const ang::dcm& R0_wb, const Eigen::Vector3d& v0_w_mps, const Eigen::Vector3d& w0_bww_rps, const Eigen::Vector3d& x_bpb_m, const Eigen::Vector3d& a_b_mps2, const Eigen::Vector3d& alpha_b_rps2); 35 | void test03(std::vector& res, const double& Deltat_sec, const double& t_sec_end, const Eigen::Vector3d& x0_wbw_m, const ang::rotv& rv0_wb, const Eigen::Vector3d& v0_w_mps, const Eigen::Vector3d& w0_bww_rps, const Eigen::Vector3d& x_bpb_m, const Eigen::Vector3d& a_b_mps2, const Eigen::Vector3d& alpha_b_rps2); 36 | void test11(std::vector& res, const double& Deltat_sec, const double& t_sec_end, const Eigen::Vector3d& x0_wbw_m, const ang::rodrigues& q0_wb, const Eigen::Vector3d& v0_b_mps, const Eigen::Vector3d& w0_bwb_rps, const Eigen::Vector3d& x_bpb_m, const Eigen::Vector3d& a_b_mps2, const Eigen::Vector3d& alpha_b_rps2); 37 | void test12(std::vector& res, const double& Deltat_sec, const double& t_sec_end, const Eigen::Vector3d& x0_wbw_m, const ang::dcm& R0_wb, const Eigen::Vector3d& v0_b_mps, const Eigen::Vector3d& w0_bwb_rps, const Eigen::Vector3d& x_bpb_m, const Eigen::Vector3d& a_b_mps2, const Eigen::Vector3d& alpha_b_rps2); 38 | void test13(std::vector& res, const double& Deltat_sec, const double& t_sec_end, const Eigen::Vector3d& x0_wbw_m, const ang::rotv& rv0_wb, const Eigen::Vector3d& v0_b_mps, const Eigen::Vector3d& w0_bwb_rps, const Eigen::Vector3d& x_bpb_m, const Eigen::Vector3d& a_b_mps2, const Eigen::Vector3d& alpha_b_rps2); 39 | }; 40 | 41 | ////////////////////////////////////////////////////////////////////////////// 42 | ////////////////////////////////////////////////////////////////////////////// 43 | 44 | 45 | } // closes namespace test 46 | } // closes namespace ang 47 | 48 | #endif 49 | 50 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/Tso3.h: -------------------------------------------------------------------------------- 1 | #ifndef ATT_TEST_SO3 2 | #define ATT_TEST_SO3 3 | 4 | #include "ang_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | /* 8 | This file contains tests to verify the proper behavior of the different methods 9 | of representing a rotation (euler, dcm, rodrigues, rotv, so3). 10 | */ 11 | 12 | namespace ang { 13 | namespace test { 14 | 15 | class Tso3: public ::jail::unit_test { 16 | public: 17 | /**< constructor based on counter */ 18 | explicit Tso3(jail::counter&); 19 | /**< execute tests and write results on console */ 20 | void run() override; 21 | 22 | /**< specific tests */ 23 | void test_so3(); 24 | void test_euler(); 25 | void test_rodrigues_jacobian(); 26 | void test_exp_log_maps_small(); 27 | void test_exp_log_maps(); 28 | void test_power(); 29 | void test_slerp(); 30 | void test_quat_4_solutions(); 31 | }; 32 | 33 | } // closes namespace test 34 | 35 | } // closes namespace ang 36 | 37 | #endif 38 | 39 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/Tspecific.h: -------------------------------------------------------------------------------- 1 | #ifndef ATT_TEST_SPECIFIC 2 | #define ATT_TEST_SPECIFIC 3 | 4 | #include "ang_test.h" 5 | #include 6 | 7 | /* 8 | This test verifies the proper transformation between BFS (Body Fixed System) and 9 | CRS (Frame Reference System), as well as between NED (North - East - Down) and 10 | ENU (East - North - Up) vectors. 11 | */ 12 | 13 | namespace ang { 14 | namespace test { 15 | 16 | class Tspecific: public ::jail::unit_test { 17 | public: 18 | /**< constructor based on counter */ 19 | explicit Tspecific(jail::counter&); 20 | /**< execute tests and write results on console */ 21 | void run() override; 22 | 23 | /**< specific tests */ 24 | void test_body_camera(); 25 | void test_skew(); 26 | }; 27 | 28 | } // closes namespace test 29 | } // closes namespace ang 30 | 31 | #endif 32 | 33 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/ang_test.h: -------------------------------------------------------------------------------- 1 | #ifndef ANG_TEST_INCLUDED 2 | #define ANG_TEST_INCLUDED 3 | 4 | // 4251: some class or template needs to have dll-interface to be used by clients 5 | // of this class. No problem when refers to templates, clients can link successfully 6 | // because the class instantiation (the code) is in client side (so no link at all). 7 | // Disabling 4251 can hide a problem when this class (which is dll exported): either 8 | // (1) expose in non-private sections or (2) use in inline functions implementations, 9 | // types witch are not dll exported 10 | // 4996: MSVC has gone into full security-paranoia mode. std::copy issues this warning 11 | // when it is used with raw pointers, because when used incorrectly, it can result in 12 | // buffer overflows. But if code is OK, no problem. Stupid Microsoft warning. 13 | #if defined(_MSC_VER) 14 | # pragma warning(disable:4251) 15 | # pragma warning(disable:4996) 16 | #endif 17 | 18 | #endif 19 | -------------------------------------------------------------------------------- /project_phd/phd/ang_test/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Tso3.h" 3 | #include "Tspecific.h" 4 | #include "Tintegration.h" 5 | #include "Tintegration.h" 6 | #include "Tcheck.h" 7 | 8 | #include 9 | 10 | int main(int argc, char **argv) { 11 | 12 | jail::counter Ocounter; 13 | 14 | {ang::test::Tso3 o(Ocounter); o.run();} 15 | {ang::test::Tcheck o(Ocounter); o.run();} 16 | {ang::test::Tspecific o(Ocounter); o.run();} 17 | {ang::test::Tintegration o(Ocounter); o.run();} 18 | 19 | Ocounter.write_results(); 20 | 21 | return 0; 22 | } 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/apm/OLDmugin_inertia_python.txt: -------------------------------------------------------------------------------- 1 | 1.9719999999999999e+01 2 | -2.0669999999999999e-01 0.0000000000000000e+00 4.9350000000000002e-03 3 | 2.0080000000000000e+00 0.0000000000000000e+00 -1.9099999999999998e-01 4 | 0.0000000000000000e+00 3.3639999999999999e+00 0.0000000000000000e+00 5 | -1.9099999999999998e-01 0.0000000000000000e+00 5.2930000000000001e+00 6 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/apm/OLDmugin_propulsion_python.txt: -------------------------------------------------------------------------------- 1 | 0.0000000000000000e+00 2.0000000000000000e-02 62 2 | 1.2674900000000000e-01 7.5074000000000002e-02 3 | 1.2775414400000001e-01 7.4064896000000005e-02 4 | 1.2859019199999999e-01 7.3261488000000000e-02 5 | 1.2922596800000000e-01 7.2674432000000011e-02 6 | 1.2963029600000001e-01 7.2314384000000009e-02 7 | 1.2977200000000000e-01 7.2192000000000006e-02 8 | 1.2966816937415215e-01 7.2367408209664211e-02 9 | 1.2939154812245646e-01 7.2815744628992637e-02 10 | 1.2899444218368469e-01 7.3420176943488943e-02 11 | 1.2852915749660862e-01 7.4063872838656841e-02 12 | 1.2804800000000000e-01 7.4630000000000002e-02 13 | 1.2750222229680264e-01 7.5123928056435862e-02 14 | 1.2682741719654911e-01 7.5623545741789144e-02 15 | 1.2605240094789422e-01 7.6120799398924494e-02 16 | 1.2520598979949291e-01 7.6607635370706570e-02 17 | 1.2431700000000000e-01 7.7076000000000006e-02 18 | 1.2336580680804830e-01 7.7544284835470809e-02 19 | 1.2231706887472940e-01 7.8018681219607630e-02 20 | 1.2117602753738634e-01 7.8472835186009046e-02 21 | 1.1994792413336218e-01 7.8880392768273633e-02 22 | 1.1863799999999999e-01 7.9214999999999994e-02 23 | 1.1722592383687093e-01 7.9513854336633660e-02 24 | 1.1568847637331302e-01 7.9808066128712871e-02 25 | 1.1402656699131965e-01 8.0062150752475247e-02 26 | 1.1224110507288419e-01 8.0240623584158413e-02 27 | 1.1033300000000000e-01 8.0308000000000004e-02 28 | 1.0824940288974980e-01 8.0204471109623435e-02 29 | 1.0596163689658229e-01 7.9923973328870301e-02 30 | 1.0350686945853990e-01 7.9511639993305447e-02 31 | 1.0092226801366501e-01 7.9012604438493728e-02 32 | 9.8244999999999999e-02 7.8472000000000000e-02 33 | 9.5412841055714306e-02 7.7773061103344004e-02 34 | 9.2384777749598052e-02 7.6817436632207733e-02 35 | 8.9229793915624647e-02 7.5677881609399464e-02 36 | 8.6016873387767492e-02 7.4427151057727459e-02 37 | 8.2815000000000000e-02 7.3137999999999995e-02 38 | 7.9624100097698464e-02 7.1770827253738373e-02 39 | 7.6397166540773206e-02 7.0254893324998055e-02 40 | 7.3132782934998725e-02 6.8616245769388545e-02 41 | 6.9829532886149487e-02 6.6880932142519361e-02 42 | 6.6486000000000003e-02 6.5074999999999994e-02 43 | 6.3085753463208105e-02 6.3170488071675676e-02 44 | 5.9628516113074029e-02 6.1136134873196565e-02 45 | 5.6137102031335907e-02 5.8993037638879628e-02 46 | 5.2634325299731874e-02 5.6762293603041802e-02 47 | 4.9143000000000020e-02 5.4465000000000013e-02 48 | 4.5659000000000019e-02 5.1992000000000010e-02 49 | 4.2154999999999998e-02 4.9408000000000001e-02 50 | 3.8621000000000003e-02 4.6703000000000001e-02 51 | 3.5085999999999999e-02 4.3901999999999997e-02 52 | 3.1101000000000000e-02 4.1270000000000001e-02 53 | 2.7493000000000000e-02 3.8238000000000001e-02 54 | 2.3864000000000000e-02 3.5089000000000002e-02 55 | 2.0220999999999999e-02 3.1829000000000003e-02 56 | 1.6538000000000001e-02 2.8431000000000001e-02 57 | 1.2834000000000000e-02 2.4912000000000000e-02 58 | 9.2110000000000438e-03 2.1387000000000038e-02 59 | 4.9319999999999998e-03 1.8217000000000001e-02 60 | 1.1869999999999999e-03 1.4407000000000000e-02 61 | -2.6180000000000001e-03 1.0432000000000000e-02 62 | -6.4559999999999999e-03 6.3200000000000001e-03 63 | -1.0238000000000001e-02 2.1809999999999998e-03 64 | 4.5000000000000001e-01 65 | 3.5000000000000000e+03 66 | 2.7000000000000000e+01 67 | 1.3000000000000000e+02 68 | -8.7266462599716480e-04 1.7453292519943296e-03 0.0000000000000000e+00 69 | 4.3169999999999997e-01 0.0000000000000000e+00 -4.9350000000000002e-03 70 | 2.2000000000000001e-07 71 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/apm/mugin_aerodynamics3_cpp.txt: -------------------------------------------------------------------------------- 1 | 8.7753999999999999e-01 2 | 3.5893999999999998e-01 3 | 2.6800000000000002e+00 4 | -2.0669999999999999e-01 0.0000000000000000e+00 4.9349999999999993e-03 5 | -1.1500000000000000e-01 6 | -1.9999999999999999e-06 9.6534999999999996e-02 -0.0000000000000000e+00 7 | -1.3104299999999999e-01 0.0000000000000000e+00 -7.5049510000000001e+00 8 | 0.0000000000000000e+00 3.7837599999999999e-01 0.0000000000000000e+00 9 | -5.3303599999999995e-01 0.0000000000000000e+00 -6.2864000000000003e-02 10 | -0.0000000000000000e+00 -1.9835037000000000e+01 0.0000000000000000e+00 11 | 1.6337199999999999e-01 -0.0000000000000000e+00 -1.9654700000000000e-01 12 | -0.0000000000000000e+00 1.2000000000000000e-05 -0.0000000000000000e+00 13 | -1.7000000000000000e-05 2.6020000000000001e-03 4.0169999999999997e-03 14 | 1.7000000000000000e-05 2.6020000000000001e-03 -4.0169999999999997e-03 15 | -4.3160000000000004e-03 -0.0000000000000000e+00 2.3300000000000000e-04 16 | -6.6000000000000005e-05 1.6022999999999999e-02 -1.4410000000000000e-03 17 | -6.6000000000000005e-05 -1.6022999999999999e-02 -1.4410000000000000e-03 18 | -2.2610000000000002e-02 0.0000000000000000e+00 -5.5115999999999998e-01 19 | -0.0000000000000000e+00 -1.4470000000000000e-02 0.0000000000000000e+00 20 | 1.1917522138721194e-02 -4.8128454790989156e-01 2.3605861159389355e-02 21 | -4.6753356082675182e-02 -3.8961130068895984e-03 9.9465473234710916e-02 22 | 4.3749999999999952e-05 0.0000000000000000e+00 -8.0162500000000025e-03 23 | 0.0000000000000000e+00 -3.2018749999999999e-02 0.0000000000000000e+00 24 | 2.4912204932288193e-01 0.0000000000000000e+00 -4.3854189639313210e+00 25 | 0.0000000000000000e+00 -1.4517604613024799e+00 0.0000000000000000e+00 26 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/apm/mugin_inertia_cpp.txt: -------------------------------------------------------------------------------- 1 | 1.9715000000000000e+01 2 | 2.0699999999999999e-01 0.0000000000000000e+00 -5.0000000000000001e-03 3 | 2.2020000000000000e+00 0.0000000000000000e+00 -1.9100000000000000e-01 4 | 0.0000000000000000e+00 3.4620000000000002e+00 0.0000000000000000e+00 5 | -1.9100000000000000e-01 0.0000000000000000e+00 5.4900000000000002e+00 6 | 1.7835000000000001e+01 7 | 2.1900000000000000e-01 0.0000000000000000e+00 -6.0000000000000001e-03 8 | 2.1980000000000000e+00 0.0000000000000000e+00 -1.9200000000000000e-01 9 | 0.0000000000000000e+00 3.4300000000000002e+00 0.0000000000000000e+00 10 | -1.9200000000000000e-01 0.0000000000000000e+00 5.4580000000000002e+00 11 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/apm/mugin_propeller.txt: -------------------------------------------------------------------------------- 1 | J Ct Cp 2 | 0 0.126749 0.075074 3 | 0.1 0.129772 0.072192 4 | 0.2 0.128048 0.07463 5 | 0.3 0.124317 0.077076 6 | 0.4 0.118638 0.079215 7 | 0.5 0.110333 0.080308 8 | 0.6 0.098245 0.078472 9 | 0.7 0.082815 0.073138 10 | 0.8 0.066486 0.065075 11 | 0.9 0.049143 0.054465 12 | 0.92 0.045659 0.051992 13 | 0.94 0.042155 0.049408 14 | 0.96 0.038621 0.046703 15 | 0.98 0.035086 0.043902 16 | 1 0.031101 0.04127 17 | 1.02 0.027493 0.038238 18 | 1.04 0.023864 0.035089 19 | 1.06 0.020221 0.031829 20 | 1.08 0.016538 0.028431 21 | 1.1 0.012834 0.024912 22 | 1.12 0.009211 0.021387 23 | 1.14 0.004932 0.018217 24 | 1.16 0.001187 0.014407 25 | 1.18 -0.002618 0.010432 26 | 1.2 -0.006456 0.00632 27 | 1.22 -0.010238 0.002181 28 | 29 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/geopotential/H2h_32_geop.txt: -------------------------------------------------------------------------------- 1 | 0.0000000000000000e+00 2 | 2.0000000000000000e+01 3 | 251 4 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/geopotential/H2h_32_lat.txt: -------------------------------------------------------------------------------- 1 | 0.0000000000000000e+00 2 | 1.7453292519943295e-02 3 | 91 4 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/geopotential/htoH_32_geom.txt: -------------------------------------------------------------------------------- 1 | 0.0000000000000000e+00 2 | 2.0000000000000000e+01 3 | 251 4 | -------------------------------------------------------------------------------- /project_phd/phd/configuration/geopotential/htoH_32_lat.txt: -------------------------------------------------------------------------------- 1 | 0.0000000000000000e+00 2 | 1.7453292519943295e-02 3 | 91 4 | -------------------------------------------------------------------------------- /project_phd/phd/env/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname env) 3 | 4 | file (GLOB dir_1_headers *.h *.hpp) 5 | source_group("" FILES ${dir_1_headers}) 6 | set(all_headers ${dir_1_headers} ) 7 | 8 | file (GLOB dir_1_sources *.cpp *.c) 9 | source_group("" FILES ${dir_1_sources}) 10 | set(all_sources ${dir_1_sources} ) 11 | 12 | string(TOUPPER ${prjname} PRJNAME) 13 | add_definitions(-D${PRJNAME}_DLL) 14 | add_definitions(-D${PRJNAME}_DLL_EXPORTS) 15 | 16 | add_library(${prjname} SHARED ${all_headers} ${all_sources}) 17 | 18 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 19 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 20 | 21 | include_directories(${PROJECTS_SRC_ROOT}/phd) 22 | 23 | # Following lines are for Windows compatibility 24 | add_definitions(-DATTITUDE_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 29 | 30 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 31 | target_link_libraries(${prjname} optimized ${A_LIB}) # adds all Eigen libraries to target 32 | endforeach() 33 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 34 | target_link_libraries(${prjname} debug ${A_LIB}) # adds all Eigen libraries to target 35 | endforeach() 36 | 37 | 38 | 39 | 40 | 41 | -------------------------------------------------------------------------------- /project_phd/phd/env/earth.cpp: -------------------------------------------------------------------------------- 1 | #include "earth.h" 2 | #include "math/logic/share.h" 3 | 4 | // CLASS EARTH 5 | // =========== 6 | // =========== 7 | 8 | env::earth::earth(math::seeder& Oseeder, 9 | env::logic::WIND_ID wind_id, env::logic::OFFSETS_ID offsets_id, env::logic::MAG_ID mag_id, env::logic::REALISM_ID realism_id, 10 | const double& turb_factor, const double& t_sec_turb_init, const int& t_sec_turb_end) 11 | : _Poffsets(nullptr), _Pwind(nullptr), _Pturb(nullptr), _Pgeo(nullptr) { 12 | 13 | _Poffsets = env::offsets::create_offsets(offsets_id, Oseeder.provide_seed(math::seeder::seeder_offsets)); 14 | _Pwind = env::wind::create_wind(wind_id, Oseeder.provide_seed(math::seeder::seeder_wind)); 15 | _Pturb = env::turb::create_turb(t_sec_turb_init, Oseeder.get_seed_order(), t_sec_turb_end, turb_factor); 16 | _Pgeo = new env::geo_mix(mag_id, realism_id, Oseeder.provide_seed(math::seeder::seeder_geo)); 17 | } 18 | /* constructor based on seeder object, identifiers for wind filed, atmospheric offsets, magnetic location, gravity and 19 | * magnetism realism, together with turbulence level factor, initial time (for turbulence), and final time (only two 20 | * values allowed as preloaded, 1000 or 5000) */ 21 | 22 | env::earth::~earth() { 23 | delete _Poffsets; 24 | delete _Pwind; 25 | delete _Pturb; 26 | delete _Pgeo; 27 | } 28 | /* destructor */ 29 | 30 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 31 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /project_phd/phd/env/earth.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_EARTH 2 | #define ENV_EARTH 3 | 4 | #include "env.h" 5 | #include "mag.h" 6 | #include "offsets.h" 7 | #include "wind.h" 8 | #include "turb.h" 9 | #include "geo.h" 10 | #include "math/logic/seeder.h" 11 | 12 | namespace env { 13 | 14 | // CLASS EARTH 15 | // =========== 16 | // =========== 17 | 18 | class ENV_API earth { 19 | private: 20 | /**< pointer to temperature and pressure offsets */ 21 | env::offsets* _Poffsets; 22 | /**< pointer to wind */ 23 | env::wind* _Pwind; 24 | /**< pointer to turbulence */ 25 | env::turb* _Pturb; 26 | /**< pointer to geodetics */ 27 | env::geo* _Pgeo; 28 | public: 29 | /**< default constructor */ 30 | earth() = delete; 31 | /**< constructor based on seeder object, identifiers for wind filed, atmospheric offsets, magnetic location, gravity and 32 | * magnetism realism, together with turbulence level factor, initial time (for turbulence), and final time (only two 33 | * values allowed as preloaded, 1000 or 5000) */ 34 | earth(math::seeder& Oseeder, 35 | env::logic::WIND_ID wind_id, env::logic::OFFSETS_ID offsets_id, env::logic::MAG_ID mag_id, env::logic::REALISM_ID realism_id, const double& turb_factor, 36 | const double& t_sec_turb_init, const int& t_sec_turb_end); 37 | /**< copy constructor */ 38 | earth(const earth&) = delete; 39 | /**< move constructor */ 40 | earth(earth&&) = delete; 41 | /**< destructor */ 42 | ~earth(); 43 | /**< copy assignment */ 44 | earth& operator=(const earth&) = delete; 45 | /**< move assignment */ 46 | earth& operator=(earth&&) = delete; 47 | 48 | /**< get temperature and pressure offsets */ 49 | const env::offsets& get_offsets() const {return *_Poffsets;} 50 | env::offsets& get_offsets() {return *_Poffsets;} 51 | /**< get wind */ 52 | const env::wind& get_wind() const {return *_Pwind;} 53 | env::wind& get_wind() {return *_Pwind;} 54 | /**< get turbulence */ 55 | const env::turb& get_turb() const {return *_Pturb;} 56 | env::turb& get_turb() {return *_Pturb;} 57 | /**< get geodetics */ 58 | const env::geo& get_geo() const {return *_Pgeo;} 59 | env::geo& get_geo() {return *_Pgeo;} 60 | }; // closes class earth 61 | 62 | }; // closes namespace env 63 | 64 | #endif 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | -------------------------------------------------------------------------------- /project_phd/phd/env/env.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Generic helper definitions for shared library support 4 | #if defined _WIN32 || defined __CYGWIN__ 5 | #define ENV_HELPER_DLL_IMPORT __declspec(dllimport) 6 | #define ENV_HELPER_DLL_EXPORT __declspec(dllexport) 7 | #define ENV_HELPER_DLL_LOCAL 8 | #else 9 | #if __GNUC__ >= 4 10 | #define ENV_HELPER_DLL_IMPORT __attribute__ ((visibility ("default"))) 11 | #define ENV_HELPER_DLL_EXPORT __attribute__ ((visibility ("default"))) 12 | #define ENV_HELPER_DLL_LOCAL __attribute__ ((visibility ("hidden"))) 13 | #else 14 | #define ENV_HELPER_DLL_IMPORT 15 | #define ENV_HELPER_DLL_EXPORT 16 | #define ENV_HELPER_DLL_LOCAL 17 | #endif 18 | #endif 19 | 20 | // Now we use the generic helper definitions above to define ENV_API and ENV_LOCAL. 21 | // ENV_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 22 | // ENV_LOCAL is used for non-api symbols. 23 | 24 | #ifdef ENV_DLL // defined if ENV is compiled as a DLL 25 | #ifdef ENV_DLL_EXPORTS // defined if we are building the ENV DLL (instead of using it) 26 | #define ENV_API ENV_HELPER_DLL_EXPORT 27 | #else 28 | #define ENV_API ENV_HELPER_DLL_IMPORT 29 | #endif // ENV_DLL_EXPORTS 30 | #define ENV_LOCAL ENV_HELPER_DLL_LOCAL 31 | #else // ENV_DLL is not defined: this means ENV is a static lib. 32 | #define ENV_API 33 | #define ENV_LOCAL 34 | #endif // ENV_DLL 35 | -------------------------------------------------------------------------------- /project_phd/phd/env/speed.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_SPEED 2 | #define ENV_SPEED 3 | 4 | #include "env.h" 5 | #include "ang/rotate/euler.h" 6 | 7 | /* 8 | This file contains the static class "speed", with methods related to the computation 9 | of the true airspeed vector in different reference frames, as well as the conversion 10 | between angular velocity and kinetic moment. */ 11 | 12 | namespace env { 13 | 14 | // CLASS SPEED 15 | // =========== 16 | // =========== 17 | 18 | class ENV_API speed { 19 | public: 20 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 21 | /**< compute the three true airspeed BFS (Body Fixed System) components [mps] based 22 | on the true airspeed modulus, the angle of attack, and the angle of sideslip. */ 23 | static Eigen::Vector3d vtas2vtasbfs(const double& vtas_mps, const ang::euler& euler_wb); 24 | /**< compute the three true airspeed NED (North - East - Down) components [mps] 25 | based on the true airspeed modulus and the NED to WFS Euler angles. */ 26 | static Eigen::Vector3d vtas2vtasned(const double& vtas_mps, const ang::euler& euler_nw); 27 | /**< compute the airspeed modulus [mps] based on the three true airspeed BFS 28 | (Body Fixed System) components. */ 29 | static double vtasbfs2vtas(const Eigen::Vector3d& vtas_b_mps); 30 | /**< compute the WFS to BFS Euler angles (minus angles of sideslip, angle of attack, 31 | zero) based on the three true airspeed BFS (Body Fixed System) components. */ 32 | static ang::euler vtasbfs2euler_wb(const Eigen::Vector3d& vtas_b_mps); 33 | /**< compute the WFS to BFS Euler angles (minus angles of sideslip, angle of attack, 34 | zero) based on the three true airspeed BFS (Body Fixed System) components and its norm. */ 35 | static ang::euler vtasbfs2euler_wb(const Eigen::Vector3d& vtas_b_mps, const double& vtas_mps); 36 | /**< Compute the differential with time of the true airspeed vector in 37 | BFS(Body Fixed System) [mps2] based on the true airspeed modulus, the angle of 38 | attack, the angle of sideslip, and their differentials with time. */ 39 | static Eigen::Vector3d vtasbfsdot(const double& vtas_mps, const ang::euler& euler_wb, const double& dvtas_dt_mps2, const Eigen::Vector3d& deuler_wb_dt_rps); 40 | /**< computes the kinetic moment [Nms] as the product of the inertial tensor by the angular speed. */ 41 | static Eigen::Vector3d omega2h(const Eigen::Matrix3d& I_kgm2, const Eigen::Vector3d& w_rps); 42 | /**< computes the angular speed [rps] based on the inertial tensor and kinetic moment */ 43 | static Eigen::Vector3d h2omega(const Eigen::Matrix3d&I_kgm2, const Eigen::Vector3d& h_Nms); 44 | }; // closes class speed 45 | 46 | //////////////////////////////////////////////////////////////////////////////////// 47 | //////////////////////////////////////////////////////////////////////////////////// 48 | 49 | }; // closes namespace env 50 | 51 | #endif 52 | 53 | 54 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname env_test) 3 | 4 | file (GLOB dir_27_headers *.h *.hpp) 5 | source_group("" FILES ${dir_27_headers}) 6 | set(all_headers ${dir_27_headers} ) 7 | 8 | file (GLOB dir_28_sources *.cpp *.c) 9 | source_group("" FILES ${dir_28_sources}) 10 | set(all_sources ${dir_28_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DATTITUDE_DLL) 21 | add_definitions(-DFDYN_DLL) 22 | add_definitions(-DJAIL_DLL) 23 | # End Windows compatibility 24 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 25 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 26 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 27 | target_link_libraries(${prjname} debug jail${DEBUG_TARGET_SUFFIX} optimized jail) 28 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 29 | 30 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 31 | target_link_libraries(${prjname} optimized ${A_LIB}) 32 | endforeach() 33 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 34 | target_link_libraries(${prjname} debug ${A_LIB}) 35 | endforeach() 36 | 37 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/Tenv_plots_phd.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_TEST_PLOTS_PHD 2 | #define ENV_TEST_PLOTS_PHD 3 | 4 | #include "env_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | /* 8 | This file contains tests to generate the PhD envENV plots. 9 | */ 10 | 11 | namespace env { 12 | namespace test { 13 | 14 | class Tenv_plots_phd: public ::jail::unit_test { 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tenv_plots_phd(jail::counter&); 18 | /**< execute tests and write results on console */ 19 | void run() override; 20 | /**< specific tests */ 21 | 22 | void test_Tp_Hp__DeltaT(); 23 | void test_H_h__phi(); 24 | void test_H_vs_Hp__DeltaT(); 25 | 26 | }; 27 | 28 | } // closes namespace test 29 | 30 | } // closes namespace env 31 | 32 | #endif 33 | 34 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/Tenvironment.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_TEST_ENVIRONMENT 2 | #define ENV_TEST_ENVIRONMENT 3 | 4 | #include "env_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | /* 8 | This file contains tests to verify the proper behavior of the files in the main folder of the "env" library. 9 | */ 10 | 11 | namespace env { 12 | namespace test { 13 | 14 | class Tenvironment: public ::jail::unit_test { 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tenvironment(jail::counter&); 18 | /**< execute tests and write results on console */ 19 | void run() override; 20 | /**< specific tests */ 21 | void test_atm(); 22 | void test_DeltaT_Deltap(); 23 | void test_atm_inverse(); 24 | void test_offsets_ramp(); 25 | void test_wind_ramp(); 26 | void test_coord(); 27 | void test_geo(); 28 | void test_speed(); 29 | }; 30 | 31 | }; // closes namespace test 32 | } // closes namespace env 33 | 34 | #endif 35 | 36 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/Tgravity.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_TEST_GRAVITY 2 | #define ENV_TEST_GRAVITY 3 | 4 | #include "env_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | /*This file verifies the proper behavior of the magnetism classes: 8 | * - test_model focuses on the model gravity, comparing the previous EGM96 ellipsoidal 9 | * gravitation plus centrifugal potential, against the new WGS84 gravity. 10 | * - test_truth obtains metrics for the difference between the model and real 11 | * gravity fields. 12 | */ 13 | 14 | namespace env { 15 | namespace test { 16 | 17 | class Tgravity: public ::jail::unit_test { 18 | public: 19 | /**< constructor based on counter */ 20 | explicit Tgravity(jail::counter&); 21 | /**< execute tests and write results on console */ 22 | void run() override; 23 | /**< specific tests */ 24 | 25 | void test_model(); 26 | void test_truth(); 27 | }; 28 | 29 | }; // closes namespace test 30 | } // closes namespace env 31 | 32 | #endif 33 | 34 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/Tmagnetic.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_TEST_MAGNETIC 2 | #define ENV_TEST_MAGNETIC 3 | 4 | #include "env_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | /* 8 | * This file verifies the proper behavior of the magnetism classes: 9 | * - test_model focuses on the model magnetic fields, which are either constant 10 | * or bilinear in longitude and latitude. 11 | * - test_truth obtains metrics for the difference between the model and real 12 | * magnetic fields. 13 | */ 14 | 15 | namespace env { 16 | namespace test { 17 | 18 | class Tmagnetic: public ::jail::unit_test { 19 | public: 20 | /**< constructor based on counter */ 21 | explicit Tmagnetic(jail::counter&); 22 | /**< execute tests and write results on console */ 23 | void run() override; 24 | /**< specific tests */ 25 | 26 | void test_model(); 27 | void test_truth(); 28 | }; 29 | 30 | }; // closes namespace test 31 | } // closes namespace env 32 | 33 | #endif 34 | 35 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/Tturb.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_TEST_TURB 2 | #define ENV_TEST_TURB 3 | 4 | #include "env_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | namespace env { 8 | namespace test { 9 | 10 | class Tturb: public ::jail::unit_test { 11 | public: 12 | /**< constructor based on counter */ 13 | explicit Tturb(jail::counter&); 14 | /**< execute tests and write results on console */ 15 | void run() override; 16 | /**< specific tests */ 17 | void test_turb(); 18 | void test_turb_obtain_differential(const double& turb_factor); 19 | }; 20 | 21 | }; // closes namespace test 22 | } // closes namespace env 23 | 24 | #endif 25 | 26 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/env_test.h: -------------------------------------------------------------------------------- 1 | #ifndef ENV_TEST_INCLUDED 2 | #define ENV_TEST_INCLUDED 3 | 4 | // 4251: some class or template needs to have dll-interface to be used by clients 5 | // of this class. No problem when reffers to templates, clients can link succesfully 6 | // because the class instantiation (the code) is in client side (so no link at all). 7 | // Disabling 4251 can hide a problem when this class (which is dll exported): either 8 | // (1) expose in non-private sections or (2) use in inline functions implementations, 9 | // types witch are not dll exported 10 | // 4996: MSVC has gone into full security-paranoia mode. std::copy issues this warning 11 | // when it is used with raw pointers, because when used incorrectly, it can result in 12 | // buffer overflows. But if code is OK, no problem. Stupid Microsoft warning. 13 | #if defined(_MSC_VER) 14 | # pragma warning(disable:4251) 15 | # pragma warning(disable:4996) 16 | #endif 17 | 18 | // Now we use the generic helper definitions above to define envENV_TEST_API and envENV_TEST_LOCAL. 19 | // envENV_TEST_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 20 | // envENV_TEST_LOCAL is used for non-api symbols. 21 | 22 | #ifdef envENV_TEST_DLL // defined if envENV_TEST is compiled as a DLL 23 | #ifdef envENV_TEST_DLL_EXPORTS // defined if we are building the envENV_TEST DLL (instead of using it) 24 | #define envENV_TEST_API envENV_HELPER_DLL_EXPORT 25 | #else 26 | #define envENV_TEST_API envENV_HELPER_DLL_IMPORT 27 | #endif // envENV_TEST_DLL_EXPORTS 28 | #define envENV_TEST_LOCAL envENV_HELPER_DLL_LOCAL 29 | #else // envENV_TEST_DLL is not defined: this means envENV_TEST is a static lib. 30 | #define envENV_TEST_API 31 | #define envENV_TEST_LOCAL 32 | #endif // envENV_TEST_DLL 33 | 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /project_phd/phd/env_test/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Tenvironment.h" 3 | #include "Tmagnetic.h" 4 | #include "Tgravity.h" 5 | #include "Tturb.h" 6 | #include "Tenv_plots_phd.h" 7 | #include 8 | 9 | int main(int argc, char **argv) { 10 | 11 | jail::counter Ocounter; 12 | 13 | {env::test::Tenvironment o(Ocounter); o.run(); } 14 | {env::test::Tmagnetic o(Ocounter); o.run(); } 15 | {env::test::Tgravity o(Ocounter); o.run(); } 16 | {env::test::Tturb o(Ocounter); o.run(); } 17 | {env::test::Tenv_plots_phd o(Ocounter); o.run(); } 18 | 19 | Ocounter.write_results(); 20 | 21 | return 0; 22 | } 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /project_phd/phd/exec_cntr/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname exec_cntr) 3 | 4 | file (GLOB dir_01_headers *.h *.hpp) 5 | source_group("" FILES ${dir_01_headers}) 6 | set(all_headers ${dir_01_headers} ) 7 | 8 | file (GLOB dir_01_sources *.cpp *.c) 9 | source_group("" FILES ${dir_01_sources}) 10 | set(all_sources ${dir_01_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DMATH_DLL) 21 | add_definitions(-DATTITUDE_DLL) 22 | add_definitions(-DEARTH_DLL) 23 | add_definitions(-DFDYN_DLL) 24 | add_definitions(-DJAIL_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 29 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 30 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/exec_gps_alter/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname exec_gps_alter) 3 | 4 | file (GLOB dir_01_headers *.h *.hpp) 5 | source_group("" FILES ${dir_01_headers}) 6 | set(all_headers ${dir_01_headers} ) 7 | 8 | file (GLOB dir_01_sources *.cpp *.c) 9 | source_group("" FILES ${dir_01_sources}) 10 | set(all_sources ${dir_01_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DMATH_DLL) 21 | add_definitions(-DATTITUDE_DLL) 22 | add_definitions(-DEARTH_DLL) 23 | add_definitions(-DFDYN_DLL) 24 | add_definitions(-DJAIL_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 29 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 30 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/exec_gps_alter_mult/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname exec_gps_alter_mult) 3 | 4 | file (GLOB dir_01_headers *.h *.hpp) 5 | source_group("" FILES ${dir_01_headers}) 6 | set(all_headers ${dir_01_headers} ) 7 | 8 | file (GLOB dir_01_sources *.cpp *.c) 9 | source_group("" FILES ${dir_01_sources}) 10 | set(all_sources ${dir_01_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DMATH_DLL) 21 | add_definitions(-DATTITUDE_DLL) 22 | add_definitions(-DEARTH_DLL) 23 | add_definitions(-DFDYN_DLL) 24 | add_definitions(-DJAIL_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 29 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 30 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/exec_gps_bench/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname exec_gps_bench) 3 | 4 | file (GLOB dir_01_headers *.h *.hpp) 5 | source_group("" FILES ${dir_01_headers}) 6 | set(all_headers ${dir_01_headers} ) 7 | 8 | file (GLOB dir_01_sources *.cpp *.c) 9 | source_group("" FILES ${dir_01_sources}) 10 | set(all_sources ${dir_01_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DMATH_DLL) 21 | add_definitions(-DATTITUDE_DLL) 22 | add_definitions(-DEARTH_DLL) 23 | add_definitions(-DFDYN_DLL) 24 | add_definitions(-DJAIL_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 29 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 30 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/exec_gps_bench_mult/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname exec_gps_bench_mult) 3 | 4 | file (GLOB dir_01_headers *.h *.hpp) 5 | source_group("" FILES ${dir_01_headers}) 6 | set(all_headers ${dir_01_headers} ) 7 | 8 | file (GLOB dir_01_sources *.cpp *.c) 9 | source_group("" FILES ${dir_01_sources}) 10 | set(all_sources ${dir_01_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DMATH_DLL) 21 | add_definitions(-DATTITUDE_DLL) 22 | add_definitions(-DEARTH_DLL) 23 | add_definitions(-DFDYN_DLL) 24 | add_definitions(-DJAIL_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 29 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 30 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/exec_nav/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname exec_nav) 3 | 4 | file (GLOB dir_01_headers *.h *.hpp) 5 | source_group("" FILES ${dir_01_headers}) 6 | set(all_headers ${dir_01_headers} ) 7 | 8 | file (GLOB dir_01_sources *.cpp *.c) 9 | source_group("" FILES ${dir_01_sources}) 10 | set(all_sources ${dir_01_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DMATH_DLL) 21 | add_definitions(-DATTITUDE_DLL) 22 | add_definitions(-DEARTH_DLL) 23 | add_definitions(-DFDYN_DLL) 24 | add_definitions(-DJAIL_DLL) 25 | # End Windows compatibility 26 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 27 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 28 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 29 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 30 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/jail/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname jail) 3 | 4 | file (GLOB dir_31_headers *.h *.hpp) 5 | source_group("" FILES ${dir_31_headers}) 6 | set(all_headers ${dir_31_headers}) 7 | 8 | file (GLOB dir_32_sources *.cpp *.c) 9 | source_group("" FILES ${dir_32_sources}) 10 | set(all_sources ${dir_32_sources}) 11 | 12 | string(TOUPPER ${prjname} PRJNAME) 13 | add_definitions(-D${PRJNAME}_DLL) 14 | add_definitions(-D${PRJNAME}_DLL_EXPORTS) 15 | 16 | add_library(${prjname} SHARED ${all_headers} ${all_sources}) 17 | 18 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 19 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 20 | 21 | include_directories(${PROJECTS_SRC_ROOT}/phd) 22 | 23 | -------------------------------------------------------------------------------- /project_phd/phd/jail/jail.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Generic helper definitions for shared library support 4 | #if defined _WIN32 || defined __CYGWIN__ 5 | #define JAIL_HELPER_DLL_IMPORT __declspec(dllimport) 6 | #define JAIL_HELPER_DLL_EXPORT __declspec(dllexport) 7 | #define JAIL_HELPER_DLL_LOCAL 8 | #else 9 | #if __GNUC__ >= 4 10 | #define JAIL_HELPER_DLL_IMPORT __attribute__ ((visibility ("default"))) 11 | #define JAIL_HELPER_DLL_EXPORT __attribute__ ((visibility ("default"))) 12 | #define JAIL_HELPER_DLL_LOCAL __attribute__ ((visibility ("hidden"))) 13 | #else 14 | #define JAIL_HELPER_DLL_IMPORT 15 | #define JAIL_HELPER_DLL_EXPORT 16 | #define JAIL_HELPER_DLL_LOCAL 17 | #endif 18 | #endif 19 | 20 | // Now we use the generic helper definitions above to define JAIL_API and JAIL_LOCAL. 21 | // JAIL_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 22 | // JAIL_LOCAL is used for non-api symbols. 23 | 24 | #ifdef JAIL_DLL // defined if JAIL is compiled as a DLL 25 | #ifdef JAIL_DLL_EXPORTS // defined if we are building the JAIL DLL (instead of using it) 26 | #define JAIL_API JAIL_HELPER_DLL_EXPORT 27 | #else 28 | #define JAIL_API JAIL_HELPER_DLL_IMPORT 29 | #endif // JAIL_DLL_EXPORTS 30 | #define JAIL_LOCAL JAIL_HELPER_DLL_LOCAL 31 | #else // JAIL_DLL is not defined: this means JAIL is a static lib. 32 | #define JAIL_API 33 | #define JAIL_LOCAL 34 | #endif // JAIL_DLL 35 | -------------------------------------------------------------------------------- /project_phd/phd/jail/unit_test.h: -------------------------------------------------------------------------------- 1 | #ifndef JAIL_UNIT_TEST 2 | #define JAIL_UNIT_TEST 3 | 4 | #include "jail.h" 5 | #include 6 | 7 | namespace jail { 8 | 9 | // CLASS COUNTER 10 | // ============= 11 | // ============= 12 | 13 | class JAIL_API counter { 14 | private: 15 | /**< true for partial tests, false for global ones */ 16 | bool _flag_partial; 17 | public: 18 | /**< constructor for global counter */ 19 | counter(); 20 | /**< constructor for partial counter based on current text index */ 21 | explicit counter(const unsigned int& id); 22 | /**< destructor */ 23 | ~counter() = default; 24 | 25 | /**< copy constructor */ 26 | counter(const counter&) = delete; 27 | /**< move constructor */ 28 | counter(counter&&) = delete; 29 | /**< copy assignment */ 30 | counter& operator=(const counter&) = delete; 31 | /**< move assignment */ 32 | counter& operator=(counter&&) = delete; 33 | 34 | /**< index of current test */ 35 | unsigned int _id; 36 | /**< number of passed tests */ 37 | unsigned int _passed; 38 | /**< number of failed tests */ 39 | unsigned int _failed; 40 | /**< index of first failed test */ 41 | unsigned int _first_failed; 42 | 43 | /**< writes the accumulated test results on the console */ 44 | void write_results(); 45 | }; // closes class counter 46 | 47 | ///////////////////////////////////////////////////////////////////////////////////////// 48 | ///////////////////////////////////////////////////////////////////////////////////////// 49 | 50 | // CLASS UNIT_TEST 51 | // =============== 52 | // =============== 53 | 54 | class JAIL_API unit_test { 55 | protected: 56 | /**< partial error counter */ 57 | jail::counter _Ocounter_partial; 58 | /**< weak pointer to global error counter */ 59 | jail::counter* _Pcounter_global; 60 | 61 | /**< writes partial counter results, and adds them to the global counter */ 62 | void finished(); 63 | public: 64 | /**< empty constructor */ 65 | unit_test() = delete; 66 | /**< constructor based on global error counter */ 67 | explicit unit_test(jail::counter& Ocounter); 68 | /**< destructor */ 69 | virtual ~unit_test(); 70 | /**< copy constructor */ 71 | unit_test(const unit_test&) = delete; 72 | /**< move constructor */ 73 | unit_test(unit_test&&) = delete; 74 | /**< copy assignment */ 75 | unit_test& operator=(const unit_test&) = delete; 76 | /**< move assignment */ 77 | unit_test& operator=(unit_test&&) = delete; 78 | 79 | /**< execute tests */ 80 | virtual void run() {} 81 | /**< evaluates two doubles with a given tolerance, writing proper messages on console */ 82 | void check(const std::string& st, const double& first, const double& second, const double& tolerance = 1e-8); 83 | /**< evaluates two booleans, writing proper messages on console */ 84 | void checkb(const std::string& st, bool first, bool second); 85 | /**< evaluates two integers, writing proper messages on console */ 86 | void checki(const std::string& st, const int& first, const int& second); 87 | }; // closes class unit_test 88 | 89 | ///////////////////////////////////////////////////////////////////////////////////////// 90 | ///////////////////////////////////////////////////////////////////////////////////////// 91 | 92 | } // closes namespace jail 93 | 94 | #endif 95 | 96 | -------------------------------------------------------------------------------- /project_phd/phd/math/classifiers.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_CLASSIFIERS_H 2 | #define MATH_CLASSIFIERS_H 3 | 4 | #include "pred/classifiers.h" 5 | #include "math/func.h" 6 | #include "math/low_pass.h" 7 | 8 | #endif 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /project_phd/phd/math/interp/ratio_mgr.cpp: -------------------------------------------------------------------------------- 1 | #include "ratio_mgr.h" 2 | 3 | // CLASS RATIO_MANAGER 4 | // =================== 5 | // =================== 6 | 7 | const unsigned short math::ratio_mgr::_init_siz = 10; 8 | /* initial size of pool */ 9 | 10 | math::ratio_mgr::ratio_mgr() 11 | : _pool_quadratic(_init_siz), _pool_cubic(_init_siz) {} 12 | /* empty constructor */ 13 | 14 | math::ratio_mgr::~ratio_mgr() { 15 | } 16 | /* destructor */ 17 | 18 | math::ratio_linear* math::ratio_mgr::from_pool_linear() { 19 | return new math::ratio_linear(); 20 | } 21 | math::ratio_quadratic* math::ratio_mgr::from_pool_quadratic() { 22 | return instance::get_instance()._pool_quadratic.from_pool(); 23 | } 24 | math::ratio_cubic* math::ratio_mgr::from_pool_cubic() { 25 | return instance::get_instance()._pool_cubic.from_pool(); 26 | } 27 | math::ratio_hermite* math::ratio_mgr::from_pool_hermite() { 28 | return new math::ratio_hermite(); 29 | } 30 | math::ratio_spline* math::ratio_mgr::from_pool_spline() { 31 | return new math::ratio_spline(); 32 | } 33 | /* returns pointer to new ratio objects taken from pools */ 34 | 35 | void math::ratio_mgr::to_pool_linear(math::ratio_linear* p) { 36 | delete p; 37 | } 38 | void math::ratio_mgr::to_pool_quadratic(math::ratio_quadratic* p) { 39 | instance::get_instance()._pool_quadratic.to_pool(p); 40 | } 41 | void math::ratio_mgr::to_pool_cubic(math::ratio_cubic* p) { 42 | instance::get_instance()._pool_cubic.to_pool(p); 43 | } 44 | void math::ratio_mgr::to_pool_hermite(math::ratio_hermite* p) { 45 | delete p; 46 | } 47 | void math::ratio_mgr::to_pool_spline(math::ratio_spline* p) { 48 | delete p; 49 | } 50 | /* adds ratio object pointer to pool */ 51 | 52 | math::ratio_linear* math::ratio_mgr::copy(const math::ratio_linear& o) { 53 | return new math::ratio_linear(o); 54 | } 55 | math::ratio_quadratic* math::ratio_mgr::copy(const math::ratio_quadratic& o) { 56 | return instance::get_instance()._pool_quadratic.copy(o); 57 | } 58 | math::ratio_cubic* math::ratio_mgr::copy(const math::ratio_cubic& o) { 59 | return instance::get_instance()._pool_cubic.copy(o); 60 | } 61 | math::ratio_hermite* math::ratio_mgr::copy(const math::ratio_hermite& o) { 62 | return new math::ratio_hermite(o); 63 | } 64 | math::ratio_spline* math::ratio_mgr::copy(const math::ratio_spline& o) { 65 | return new math::ratio_spline(o); 66 | } 67 | /* returns pointer to new ratio object taken from pool equal to input */ 68 | 69 | 70 | -------------------------------------------------------------------------------- /project_phd/phd/math/interp/ratio_mgr.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_RATIO_MGR_H 2 | #define MATH_RATIO_MGR_H 3 | 4 | #include "../math.h" 5 | #include "ratio.h" 6 | #include "../templates/pool_.h" 7 | #include "../templates/singleton_holder_.h" 8 | 9 | /* 10 | This file contains the ratio_mgr class (singleton), which contains four pools of 11 | ratio models (for interpolation) of classes ratio_linear, ratio_quadratic, 12 | ratio_cubic, and ratio_spline respectively. 13 | 14 | ACCURACY: 15 | - N/A 16 | 17 | LEFT: 18 | - N/A. 19 | 20 | MODE OF USE: 21 | Employ the methods (from_pool, copy, to_pool) instead of the ratio classes methods 22 | (constructor, copy_constructor, destructor). This avoids the unnecessary (and slightly 23 | expensive) constructions and deletions during the program execution. Once a ratio model 24 | is no longer required, it is returned to the pool as it is (it is not reset - although 25 | a dummy reset method is called - as it would be expensive to do so and the ratio object 26 | is updated before further use anyway) so it can be employed again, instead of deleting 27 | it to construct it later. This is done automatically by the to_pool method. 28 | In case of the ratio_linear and ratio_spline models, there are no pools as the creation 29 | is quite cheap. 30 | */ 31 | 32 | namespace math { 33 | 34 | // CLASS RATIO_MANAGER 35 | // =================== 36 | // =================== 37 | 38 | class MATH_API ratio_mgr { 39 | private: 40 | ratio_mgr(); 41 | /**< empty constructor */ 42 | ratio_mgr(const ratio_mgr&); 43 | /**< copy constructor not implemented */ 44 | ratio_mgr& operator=(const ratio_mgr&); 45 | /**< overloaded operator = (assignment) not implemented */ 46 | typedef math::singleton_holder_ instance; 47 | /**< simplify name within class */ 48 | 49 | static const unsigned short _init_siz; 50 | /**< initial size of pool */ 51 | typedef math::pool_ pool_quadratic; 52 | typedef math::pool_ pool_cubic; 53 | /** simplify names within class */ 54 | pool_quadratic _pool_quadratic; 55 | pool_cubic _pool_cubic; 56 | /**< pools of ratio_quadratic and ratio_cubic models */ 57 | public: 58 | friend class math::singleton_holder_; 59 | /**< template can access private methods */ 60 | virtual ~ratio_mgr(); 61 | /**< destructor */ 62 | 63 | static math::ratio_linear* from_pool_linear(); 64 | static math::ratio_quadratic* from_pool_quadratic(); 65 | static math::ratio_cubic* from_pool_cubic(); 66 | static math::ratio_hermite* from_pool_hermite(); 67 | static math::ratio_spline* from_pool_spline(); 68 | /**< returns pointer to new ratio objects taken from pools */ 69 | static void to_pool_linear(math::ratio_linear* p); 70 | static void to_pool_quadratic(math::ratio_quadratic* p); 71 | static void to_pool_cubic(math::ratio_cubic* p); 72 | static void to_pool_hermite(math::ratio_hermite* p); 73 | static void to_pool_spline(math::ratio_spline* p); 74 | /**< adds ratio object pointer to pool */ 75 | static math::ratio_linear* copy(const math::ratio_linear& o); 76 | static math::ratio_quadratic* copy(const math::ratio_quadratic& o); 77 | static math::ratio_cubic* copy(const math::ratio_cubic& o); 78 | static math::ratio_hermite* copy(const math::ratio_hermite& o); 79 | static math::ratio_spline* copy(const math::ratio_spline& o); 80 | /**< returns pointer to new ratio object taken from pool equal to input */ 81 | }; // closes class ratio_mgr 82 | 83 | } // closes namespace math 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /project_phd/phd/math/logic/constant.cpp: -------------------------------------------------------------------------------- 1 | #include "constant.h" 2 | 3 | // CONSTANT 4 | // ======== 5 | // ======== 6 | 7 | const double math::constant::_PI = acos(-1.); 8 | /* number PI */ 9 | 10 | const double math::constant::_PIHALF = acos(-1.) / 2.0; 11 | /* number PI / 2 */ 12 | 13 | const double math::constant::_INF = std::numeric_limits::infinity(); 14 | /* infinite */ 15 | 16 | const double math::constant::_EPS = std::numeric_limits::epsilon(); 17 | /* epsilon (machine floating point precision) */ 18 | 19 | const double math::constant::_D2R = acos(-1.) / 180.; 20 | /* conversion from degrees to radians */ 21 | 22 | const double math::constant::_R2D = 180. / acos(-1.); 23 | /* conversion from radians to degrees */ 24 | 25 | const unsigned short math::constant::_NUM_ITER = 100; 26 | /* default maximum number of iterations */ 27 | 28 | const double math::constant::_TOL = 1e-8; 29 | /* tolerance [isu units] for differences between numbers */ 30 | 31 | const double math::constant::_DIFF = 1e-12; 32 | /* tolerance [isu units] for differences between numbers in equispaced tables */ 33 | 34 | const double math::constant::_SMALL_ROT = 1e-14; 35 | /* minimum rotation in exponential map (from rotation vector to quaternion) below 36 | * which a truncated formula shall be employed, being faster and safer. Value of 3e-8 comes 37 | * from Tso3:test_exp_log_small. I set it much lower. */ 38 | 39 | const double math::constant::_GEODESIC_TOL = 1e-12; 40 | /* default tolerance [rad] for geodesic computations */ 41 | 42 | const double math::constant::_SAME_POINT_TOL = 1e-10; 43 | /* default longitude and latitude tolerance [rad] to establish if two points are the same */ 44 | 45 | /////////////////////////////////////////////////////////////////////////////// 46 | /////////////////////////////////////////////////////////////////////////////// 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | -------------------------------------------------------------------------------- /project_phd/phd/math/logic/constant.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_CONSTANT_H 2 | #define MATH_CONSTANT_H 3 | 4 | #include "../math.h" 5 | #include "logic.h" 6 | #include 7 | #include 8 | 9 | namespace math { 10 | 11 | // CONSTANT 12 | // ======== 13 | // ======== 14 | 15 | class MATH_API constant { 16 | private: 17 | /**< number PI */ 18 | static const double _PI; 19 | /**< number PI/2 */ 20 | static const double _PIHALF; 21 | /**< infinite */ 22 | static const double _INF; 23 | /**< epsilon */ 24 | static const double _EPS; 25 | /**< conversion from degrees to radians */ 26 | static const double _D2R; 27 | /**< conversion from radians to degrees */ 28 | static const double _R2D; 29 | /**< default maximum number of iterations */ 30 | static const unsigned short _NUM_ITER; 31 | /**< tolerance [isu units] for differences between numbers */ 32 | static const double _TOL; 33 | /**< tolerance [isu units] for differences between numbers in equispaced tables. */ 34 | static const double _DIFF; 35 | /**< minimum rotation in exponential map (from rotation vector to quaternion) below 36 | * which a truncated formula shall be employed, being faster and safer. Value comes 37 | * from Tso3:test_exp_log_small. */ 38 | static const double _SMALL_ROT; 39 | /**< default tolerance [rad] for geodesic computations */ 40 | static const double _GEODESIC_TOL; 41 | /**< default longitude and latitude tolerance [rad] to establish if two points are the same */ 42 | static const double _SAME_POINT_TOL; 43 | public: 44 | /**< returns number PI */ 45 | static const double& PI() {return _PI;} 46 | /**< returns number PI / 2 */ 47 | static const double& PIHALF() {return _PIHALF;} 48 | /**< returns infinite */ 49 | static const double& INF() {return _INF;} 50 | /**< returns epsilon (machine floating point precision) */ 51 | static const double& EPS() {return _EPS;} 52 | /**< returns conversion from degrees to radians */ 53 | static const double& D2R() { return _D2R; } 54 | /**< returns conversion from radians to degrees */ 55 | static const double& R2D() { return _R2D; } 56 | /**< returns default maximum number of iterations */ 57 | static const unsigned short& NUM_ITER() {return _NUM_ITER;} 58 | /**< returns tolerance [isu units] for differences between numbers */ 59 | static const double& TOL() {return _TOL;} 60 | /**< returns tolerance [isu units] for differences between numbers in equispaced tables. */ 61 | static const double& DIFF() {return _DIFF;} 62 | /**< returns minimum rotation in exponential map (from rotation vector to quaternion) below 63 | * which a truncated formula shall be employed, being faster and safer. Value comes 64 | * from Tso3:test_exp_log_small. */ 65 | static const double & SMALL_ROT() {return _SMALL_ROT;} 66 | /**< return default tolerance [rad] for geodesic computations */ 67 | static const double& GEODESIC_TOL() {return _GEODESIC_TOL;} 68 | /**< return default longitude and latitude tolerance [rad] to establish if two points are the same */ 69 | static const double& SAME_POINT_TOL() {return _SAME_POINT_TOL;} 70 | 71 | }; // closes class constant 72 | 73 | } // closes namespace math 74 | 75 | #endif 76 | 77 | 78 | -------------------------------------------------------------------------------- /project_phd/phd/math/logic/logic.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_LOGIC_H 2 | #define MATH_LOGIC_H 3 | 4 | #include "../math.h" 5 | 6 | namespace math { 7 | namespace logic { 8 | 9 | // ENUM PRED_NAME 10 | // ============== 11 | // ============== 12 | 13 | enum PRED_NAME { 14 | f_null = 0, // 0 variables: null 15 | f_constant = 1, // 0 variables: constant 16 | f_lineal = 2, // 1 variable: lineal 17 | f_parabolic = 3, // 1 variable: parabolic 18 | f_cubic = 4, // 1 variable: cubic 19 | f_steps = 5, // 1 variable: constant steps 20 | f_table1V = 6, // 1 variable: uni dimensional table 21 | f_cat = 7, // 1 variable: concatenation 22 | f_cat_partial = 8, // 1 variable: concatenation #2 23 | f_table1V_num = 9, // 1 variable:: numeric uni dimensional table with linear interpolation (avoid use if possible) 24 | f_table1V_spl = 10, // 1 variable:: numeric uni dimensional table with spline interpolation (avoid use if possible) 25 | f_lineal_double = 11, // 2 variables: lineal 26 | f_table2V = 12, // 2 variables: bi dimensional table 27 | f_lineal_triple = 13, // 3 variables: lineal 28 | f_table3V = 14, // 3 variables: tri dimensional table 29 | f_tabular3V = 15, // 3 variables: vector of bidimensional tables 30 | f_table4V = 16, // 4 variables: quatri dimensional table 31 | f_tabular2V = 17, 32 | pred_size = 18 // contains size of enumeration 33 | }; 34 | /**< enumeration that contains the names of the different predicates accepted by the fun objects. */ 35 | 36 | // ENUM INTERP_MODE 37 | // ======================= 38 | 39 | enum INTERP_MODE { 40 | lagrange_first_precompute = 0, // Lagrange 1st order interpolation (based on 2 magnitudes) with the differentials precomputed 41 | lagrange_first = 1, // Lagrange 1st order interpolation (based on 2 magnitudes) 42 | lagrange_second = 2, // Lagrange 2nd order interpolation (based on 3 magnitudes) 43 | lagrange_third = 3, // Lagrange 3rd order interpolation (based on 4 magnitudes) 44 | biparabolic = 4, // biparabolic interpolation (based on 4 magnitudes) 45 | hermite_first = 5, // Hermite cubic interpolation (differentials based on averages of Lagrange 1st order) (based on 2 magnitudes) 46 | hermite_second = 6, // Hermite cubic interpolation (differentials based on Lagrange 2nd order) (based on 2 magnitudes) 47 | spline = 7 // splines (based on 4 magnitudes) (differentials at border based on Lagrange 3rd order) 48 | //interpolation_size = 8 // BETTER WITHOUT IT 49 | }; 50 | /**< enumeration settings that indicates the interpolation method to employ for tables */ 51 | 52 | } // closes namespace logic 53 | } // closes namespace math 54 | 55 | #endif 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | -------------------------------------------------------------------------------- /project_phd/phd/math/logic/share.cpp: -------------------------------------------------------------------------------- 1 | #include "share.h" 2 | #include 3 | 4 | /////////////////////////////////////////////////////////////////////////////// 5 | /////////////////////////////////////////////////////////////////////////////// 6 | 7 | // CLASS SHARE 8 | // =========== 9 | // =========== 10 | 11 | #ifdef _WIN32 12 | # define PATHSEPARATOR '\\' 13 | #else 14 | # define PATHSEPARATOR '/' 15 | #endif 16 | 17 | std::string get_env_path(const std::string& key) { 18 | char *val; 19 | std::string path; 20 | 21 | val = std::getenv(key.c_str()); // get environment variable 22 | if (val != 0) { 23 | path = val; 24 | if (path.empty() == false) { 25 | if (path[path.size()-1] != PATHSEPARATOR) { 26 | path += PATHSEPARATOR; 27 | } 28 | } 29 | } 30 | if (path.empty() == true) { 31 | std::cerr << "CONFIGURATION_PREFIX environment variable not set." << std::endl; 32 | throw ""; 33 | } 34 | return path; 35 | } 36 | /* returns the full path of global variable of name "key" */ 37 | //} // closes generic namespace 38 | 39 | std::string math::share::phd_configuration_prefix = get_env_path("GIT_CONFIGURATION_PREFIX"); 40 | /* folder where library configuration data is located, based on GIT_CONFIGURATION_PREFIX global variable */ 41 | 42 | std::string math::share::phd_inputs_prefix = get_env_path("GIT_INPUTS_PREFIX"); 43 | /* folder where library inputs data is located, based on GIT_INPUTS_PREFIX global variable */ 44 | 45 | std::string math::share::phd_outputs_prefix = get_env_path("GIT_OUTPUTS_PREFIX"); 46 | /* folder where library outputs data is located, based on GIT_OUTPUTS_PREFIX global variable */ 47 | 48 | std::string math::share::phd_outputs_store_prefix = get_env_path("GIT_OUTPUTS_STORE_PREFIX"); 49 | /* folder where library outputs data is located, based on GIT_OUTPUTS_STORE_PREFIX global variable */ 50 | 51 | /////////////////////////////////////////////////////////////////////////////// 52 | /////////////////////////////////////////////////////////////////////////////// -------------------------------------------------------------------------------- /project_phd/phd/math/logic/share.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_SHARE 2 | #define MATH_SHARE 3 | 4 | #include "../math.h" 5 | 6 | #include 7 | 8 | namespace math { 9 | 10 | // CLASS SHARE 11 | // =========== 12 | // =========== 13 | 14 | class MATH_API share { 15 | public: 16 | /**< folder where library configuration data is located, based on GIT_CONFIGURATION_PREFIX global variable */ 17 | static std::string phd_configuration_prefix; 18 | /**< folder where library input data is located, based on GIT_INPUTS_PREFIX global variable */ 19 | static std::string phd_inputs_prefix; 20 | /**< folder where library output data is located, based on GIT_OUTPUTS_PREFIX global variable */ 21 | static std::string phd_outputs_prefix; 22 | /**< folder where library output data is located in external file, based on GIT_OUTPUTS_STORE_PREFIX global variable */ 23 | static std::string phd_outputs_store_prefix; 24 | }; // closes class share 25 | 26 | } // closes namespace math 27 | 28 | #endif 29 | -------------------------------------------------------------------------------- /project_phd/phd/math/logic/timer.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_TIMER 2 | #define MATH_TIMER 3 | 4 | #include "../math.h" 5 | #include 6 | 7 | namespace math { 8 | 9 | // CLASS TIMER 10 | // =========== 11 | // =========== 12 | 13 | class MATH_API timer { 14 | private: 15 | /**< time stamp for the last execution of the method "start" */ 16 | std::chrono::high_resolution_clock::time_point _start_time; 17 | /**< time stamp for the last execution of the method "stop" */ 18 | std::chrono::high_resolution_clock::time_point _stop_time; 19 | public: 20 | /**< starts the clock, time stamping the current time */ 21 | void start() {_start_time = std::chrono::high_resolution_clock::now();} 22 | /**< stops the clock, time stamping the current time */ 23 | void stop() {_stop_time = std::chrono::high_resolution_clock::now();} 24 | /**< returns the time difference [nanoseconds] between the last time 25 | the "stop" and "start" methods were executed */ 26 | double measure() const { 27 | return std::chrono::duration_cast(_stop_time - _start_time).count(); 28 | } 29 | }; // closes class timer 30 | 31 | } // closes namespace math 32 | 33 | #endif 34 | 35 | 36 | -------------------------------------------------------------------------------- /project_phd/phd/math/math.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Generic helper definitions for shared library support 4 | #if defined _WIN32 || defined __CYGWIN__ 5 | #define MATH_HELPER_DLL_IMPORT __declspec(dllimport) 6 | #define MATH_HELPER_DLL_EXPORT __declspec(dllexport) 7 | #define MATH_HELPER_DLL_LOCAL 8 | #else 9 | #if __GNUC__ >= 4 10 | #define MATH_HELPER_DLL_IMPORT __attribute__ ((visibility ("default"))) 11 | #define MATH_HELPER_DLL_EXPORT __attribute__ ((visibility ("default"))) 12 | #define MATH_HELPER_DLL_LOCAL __attribute__ ((visibility ("hidden"))) 13 | #else 14 | #define MATH_HELPER_DLL_IMPORT 15 | #define MATH_HELPER_DLL_EXPORT 16 | #define MATH_HELPER_DLL_LOCAL 17 | #endif 18 | #endif 19 | 20 | // Now we use the generic helper definitions above to define MATH_API and MATH_LOCAL. 21 | // MATH_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 22 | // MATH_LOCAL is used for non-api symbols. 23 | 24 | #ifdef MATH_DLL // defined if MATH is compiled as a DLL 25 | #ifdef MATH_DLL_EXPORTS // defined if we are building the MATH DLL (instead of using it) 26 | #define MATH_API MATH_HELPER_DLL_EXPORT 27 | #else 28 | #define MATH_API MATH_HELPER_DLL_IMPORT 29 | #endif // MATH_DLL_EXPORTS 30 | #define MATH_LOCAL MATH_HELPER_DLL_LOCAL 31 | #else // MATH_DLL is not defined: this means MATH is a static lib. 32 | #define MATH_API 33 | #define MATH_LOCAL 34 | #endif // MATH_DLL 35 | -------------------------------------------------------------------------------- /project_phd/phd/math/math/linear_fit_lsq.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_LINEAR_FIT_LSQ 2 | #define MATH_LINEAR_FIT_LSQ 3 | 4 | #include "../math.h" 5 | #include 6 | #include 7 | 8 | namespace math { 9 | 10 | /* 11 | * Implements a linear least squares fitting with a straight line 12 | */ 13 | 14 | // CLASS LINEAR_FIT_LSQ 15 | // ==================== 16 | // ==================== 17 | 18 | class MATH_API linear_fit_lsq { 19 | private: 20 | 21 | public: 22 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 23 | /**< default constructor */ 24 | linear_fit_lsq() = delete; 25 | /**< copy constructor */ 26 | linear_fit_lsq(const linear_fit_lsq&) = delete; 27 | /**< move constructor */ 28 | linear_fit_lsq(linear_fit_lsq&&) = delete; 29 | /**< destructor */ 30 | ~linear_fit_lsq() = default; 31 | /**< copy assignment */ 32 | linear_fit_lsq& operator=(const linear_fit_lsq&) = delete; 33 | /**< move assignment */ 34 | linear_fit_lsq& operator=(linear_fit_lsq&&) = delete; 35 | 36 | /**< XXXXXXXXXXXXXXXXXXXXXXXXXXx */ 37 | static void compute(Eigen::Vector2d& x, double& err_mean, double& err_std, Eigen::VectorXd& err, const Eigen::MatrixXd& in, const Eigen::MatrixXd& out); 38 | }; // closes class linear_fit_lsq 39 | 40 | 41 | } // closes namespace math 42 | 43 | #endif 44 | 45 | -------------------------------------------------------------------------------- /project_phd/phd/math/pred/classifiers.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_PRED_CLASSIFIERS_H 2 | #define MATH_PRED_CLASSIFIERS_H 3 | 4 | #include "pred1v/f_table1V.h" 5 | #include "pred2v/f_table2V.h" 6 | #include "pred3v/f_table3V.h" 7 | 8 | #endif 9 | -------------------------------------------------------------------------------- /project_phd/phd/math/pred/pred.cpp: -------------------------------------------------------------------------------- 1 | #include "pred.h" 2 | 3 | 4 | // CLASS PRED 5 | // ========== 6 | // ========== 7 | 8 | const std::string math::pred::describe_pred(const math::logic::PRED_NAME index) { 9 | switch(index) { 10 | case math::logic::f_null: return("f_null"); break; 11 | case math::logic::f_constant: return("f_constant"); break; 12 | case math::logic::f_lineal: return("f_lineal"); break; 13 | case math::logic::f_parabolic: return("f_parabolic"); break; 14 | case math::logic::f_cubic: return("f_cubic"); break; 15 | case math::logic::f_steps: return("f_steps"); break; 16 | case math::logic::f_table1V: return("f_table1V"); break; 17 | case math::logic::f_cat: return("f_cat"); break; 18 | case math::logic::f_cat_partial: return("f_cat_partial"); break; 19 | case math::logic::f_table1V_num: return("f_table1V_num"); break; 20 | case math::logic::f_table1V_spl: return("f_table1V_spl"); break; 21 | case math::logic::f_lineal_double: return("f_lineal_double"); break; 22 | case math::logic::f_table2V: return("f_table2V"); break; 23 | case math::logic::f_lineal_triple: return("f_lineal_triple"); break; 24 | case math::logic::f_table3V: return("f_table3V"); break; 25 | case math::logic::f_tabular3V: return("f_tabular3V"); break; 26 | case math::logic::f_table4V: return("f_table4V"); break; 27 | default: 28 | throw std::runtime_error("Incorrect predicate name.");; 29 | return(""); 30 | break; 31 | } 32 | } 33 | /* returns a string containing the name of the predicate in the 34 | PRED_NAME enumeration */ 35 | 36 | const math::logic::PRED_NAME math::pred::reverse_describe_pred(const std::string& st) { 37 | if (st == "f_null" ) {return math::logic::f_null;} 38 | else if (st == "f_constant" ) {return math::logic::f_constant;} 39 | else if (st == "f_lineal" ) {return math::logic::f_lineal;} 40 | else if (st == "f_parabolic" ) {return math::logic::f_parabolic;} 41 | else if (st == "f_cubic" ) {return math::logic::f_cubic;} 42 | else if (st == "f_steps" ) {return math::logic::f_steps;} 43 | else if (st == "f_table1V" ) {return math::logic::f_table1V;} 44 | else if (st == "f_table1Veq" ) {return math::logic::f_table1V;} 45 | else if (st == "f_cat" ) {return math::logic::f_cat;} 46 | else if (st == "f_cat_partial" ) {return math::logic::f_cat_partial;} 47 | else if (st == "f_table1V_num" ) {return math::logic::f_table1V_num;} 48 | else if (st == "f_table1V_spl" ) {return math::logic::f_table1V_spl;} 49 | else if (st == "f_lineal_double" ) {return math::logic::f_lineal_double;} 50 | else if (st == "f_table2V" ) {return math::logic::f_table2V;} 51 | else if (st == "f_table2Veq" ) {return math::logic::f_table2V;} 52 | else if (st == "f_lineal_triple" ) {return math::logic::f_lineal_triple;} 53 | else if (st == "f_table3V" ) {return math::logic::f_table3V;} 54 | else if (st == "f_table3Veq" ) {return math::logic::f_table3V;} 55 | else if (st == "f_tabular3V" ) {return math::logic::f_tabular3V;} 56 | else if (st == "f_table4V" ) {return math::logic::f_table4V;} 57 | else if (st == "f_table4Veq" ) {return math::logic::f_table4V;} 58 | else { 59 | throw std::runtime_error("Incorrect predicated name."); 60 | return math::logic::pred_size; 61 | } 62 | } 63 | /* returns the name of the predicate in the PRED_NAME enumeration based on a 64 | string describing it */ 65 | 66 | 67 | 68 | 69 | 70 | 71 | -------------------------------------------------------------------------------- /project_phd/phd/math/pred/pred.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_PRED_H 2 | #define MATH_PRED_H 3 | 4 | #include "../math.h" 5 | #include "../vec/classifiers.h" 6 | #include "range_checker.h" 7 | #include "pos_finder.h" 8 | #include "../interp/interp_lagrange_third.h" 9 | #include "../interp/interp_lagrange_second.h" 10 | #include "../interp/interp_lagrange_first.h" 11 | 12 | /* 13 | This file contains the base class for all predicates. 14 | */ 15 | 16 | namespace math { 17 | 18 | // CLASS PRED 19 | // ========== 20 | // ========== 21 | 22 | class MATH_API pred { 23 | public: 24 | virtual const logic::PRED_NAME& get_name() const = 0; 25 | /**< returns the specific predicate name */ 26 | virtual const std::string& get_st_name() const = 0; 27 | /**< returns string containing the predicate name */ 28 | virtual pred* clone() const = 0; 29 | /**< cloner */ 30 | virtual ~pred() {} 31 | /**< destructor */ 32 | static const std::string describe_pred(const math::logic::PRED_NAME index); 33 | /**< returns a string containing the name of the predicate in the 34 | PRED_NAME enumeration */ 35 | static const math::logic::PRED_NAME reverse_describe_pred(const std::string&); 36 | /**< returns the name of the predicate in the PRED_NAME enumeration based on a 37 | string describing it */ 38 | }; // closes class pred 39 | 40 | } // closes namespace math 41 | 42 | #endif 43 | 44 | 45 | 46 | -------------------------------------------------------------------------------- /project_phd/phd/math/pred/pred0v/pred0v.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_PRED0V_H 2 | #define MATH_PRED0V_H 3 | 4 | #include "../../math.h" 5 | #include "../pred.h" 6 | 7 | /* 8 | This file contains the base class pred0v for those function predicates that do 9 | not have any independent magnitudes. The derivate classes are in other files 10 | in this same folder. It is structured as a virtual base class (pred0v) with its 11 | derived implementations: f_null (returning 0) and f_constant (returning a 12 | constant value f0). 13 | 14 | No matter the inserted output units, they are immediately converted to standard 15 | ones. When employing the value method, it is already assummed that the units of 16 | the output magnitude are set OK (standard units), as this function does not 17 | make any unit checks. 18 | 19 | They all share the methods value() and differential(). 20 | Their results are: 21 | - f_null value() = 0 d_dt() = 0 22 | - f_constant value() = _f0 d_dt() = 0 23 | 24 | SLOW FUNCTIONS: 25 | - None 26 | 27 | ACCURACY: 28 | - No method presents any degradation in accuracy 29 | 30 | MODE OF USE: 31 | Employ the constructors to create instances of both classes: 32 | - f_null pred creates an object predicate of class f_null, without any 33 | input parameters. 34 | - f_constant pred(f0) creates an object predicate of class f_constant 35 | with f0 as its parameter, expressed in standard units. 36 | f_constant pred(f0, unit) shall be used when f0 is in a different unit. 37 | The functions value() and d_dt() can then be directly used, although it 38 | is more common for these objects to be the first input parameters of the fun 39 | constructors. 40 | */ 41 | 42 | namespace math { 43 | 44 | // CLASS PRED0V 45 | // ============ 46 | // ============ 47 | 48 | class MATH_API pred0v : public pred { 49 | private: 50 | 51 | 52 | public: 53 | virtual double value() const = 0; 54 | /**< evaluates the function at any point. */ 55 | virtual double d_dt() const = 0; 56 | /**< evaluates the function differential with time at any point. */ 57 | virtual const logic::PRED_NAME& get_name() const = 0; 58 | /**< see virtual function of class pred above */ 59 | virtual const std::string& get_st_name() const = 0; 60 | /**< see virtual function of class pred above */ 61 | virtual bool operator==(const pred0v& op2) const = 0; 62 | /**< overloaded operator == (equal) */ 63 | inline virtual bool operator!=(const pred0v& op2) const {return !(*this == op2);} 64 | /**< overloaded operator != (not equal) */ 65 | virtual ~pred0v() {} 66 | /**< destructor */ 67 | 68 | }; // closes class pred0v 69 | 70 | } // closes namespace math 71 | 72 | #endif 73 | 74 | 75 | 76 | -------------------------------------------------------------------------------- /project_phd/phd/math/pred/range_checker.cpp: -------------------------------------------------------------------------------- 1 | #include "range_checker.h" 2 | 3 | // CLASS RANGE_CHECKER_INACTIVE 4 | // ============================ 5 | // ============================ 6 | 7 | math::range_checker_inactive* math::range_checker_inactive::clone() const { 8 | return new math::range_checker_inactive(); 9 | } 10 | /* cloner */ 11 | 12 | ///////////////////////////////////////////////////////////////////////////////// 13 | ///////////////////////////////////////////////////////////////////////////////// 14 | 15 | // CLASS RANGE_CHECKER_ACTIVE 16 | // ========================== 17 | // ========================== 18 | 19 | void math::range_checker_active::check_range(const vec1& Ovec1, 20 | const double& o) const { 21 | bool flag = false; 22 | if (math::check_range(Ovec1.front(), Ovec1.back(), o, flag) == false) { 23 | throw std::runtime_error("Out of range."); 24 | } 25 | } 26 | /* checks if the input magnitude is within the range defined by the input 27 | vector of magnitudes. If not, returns an exception. */ 28 | 29 | math::range_checker_active* math::range_checker_active::clone() const { 30 | return new math::range_checker_active(); 31 | } 32 | /* cloner */ 33 | 34 | ///////////////////////////////////////////////////////////////////////////////// 35 | ///////////////////////////////////////////////////////////////////////////////// 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | -------------------------------------------------------------------------------- /project_phd/phd/math/pred/range_checker.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_RANGE_CHECKER_H 2 | #define MATH_RANGE_CHECKER_H 3 | 4 | #include "../math.h" 5 | #include "../vec/vec1.h" 6 | 7 | /* 8 | This file contains the functor in charge of verifying whether a given input 9 | magnitude fits within a given range. It is used by table functions to 10 | check if obtaining the result requires extrapolation or interpolation. 11 | 12 | Two options are present: active (verifies the range) and inactive (no action). 13 | */ 14 | 15 | namespace math { 16 | 17 | // CLASS RANGE_CHECKER 18 | // =================== 19 | // =================== 20 | 21 | class MATH_API range_checker { 22 | public: 23 | virtual void check_range(const vec1&, const double&) const = 0; 24 | /**< checks if the input magnitude is within the range defined by the input 25 | vector of magnitudes. If not, returns an exception. */ 26 | virtual range_checker* clone() const = 0; 27 | /**< cloner */ 28 | }; // closes class range_checker 29 | 30 | ///////////////////////////////////////////////////////////////////////////////// 31 | ///////////////////////////////////////////////////////////////////////////////// 32 | 33 | // CLASS RANGE_CHECKER_INACTIVE 34 | // ============================ 35 | // ============================ 36 | 37 | class MATH_API range_checker_inactive : public range_checker { 38 | void check_range(const vec1&, const double&) const {} 39 | /**< checks if the input magnitude is within the range defined by the input 40 | vector of magnitudes. If not, returns an exception. */ 41 | range_checker_inactive* clone() const; 42 | /**< cloner */ 43 | }; // closes class range_checker_inactive 44 | 45 | ///////////////////////////////////////////////////////////////////////////////// 46 | ///////////////////////////////////////////////////////////////////////////////// 47 | 48 | // CLASS RANGE_CHECKER_ACTIVE 49 | // ========================== 50 | // ========================== 51 | 52 | class MATH_API range_checker_active : public range_checker { 53 | void check_range(const vec1&, const double&) const; 54 | /**< checks if the input magnitude is within the range defined by the input 55 | vector of magnitudes. If not, returns an exception. */ 56 | range_checker_active* clone() const; 57 | /**< cloner */ 58 | }; // closes class range_checker_active 59 | 60 | ///////////////////////////////////////////////////////////////////////////////// 61 | ///////////////////////////////////////////////////////////////////////////////// 62 | 63 | } // closes namespace math 64 | 65 | #endif 66 | 67 | 68 | -------------------------------------------------------------------------------- /project_phd/phd/math/templates/pool_.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_POOL 2 | #define MATH_POOL 3 | 4 | #include "../math.h" 5 | #include 6 | #include 7 | #include 8 | 9 | /* 10 | This file implements the template pool_, whose purpose is to facilitate 11 | the reuse of objects which are expensive to create and delete, but can 12 | be returned to their initial state with the method reset(). If all object 13 | intances are taken and returned to the pool, no instance is deleted until 14 | the pool is deleted. The pool is initialized to a given number (input) of 15 | objects, and then increased if necessary. 16 | 17 | MODE OF USE: 18 | Obtain a new object pointer with the method from_pool(). When no longer 19 | necessary, return it to the pool for resetting enabling its reutilization 20 | with the method to_pool(). Obtain a new object pointer equal to another 21 | one with the method copy(). 22 | */ 23 | 24 | 25 | namespace math { 26 | 27 | // TEMPLATE POOL 28 | // ============= 29 | // ============= 30 | 31 | template 32 | class pool_ { 33 | private: 34 | std::vector _vec; 35 | /**< vector containing typenames F. */ 36 | pool_(const pool_&); 37 | /**< copy constructor not implemented */ 38 | pool_& operator=(const pool_&); 39 | /**< overloaded operator = (assignment) not implemented */ 40 | public: 41 | typedef F type; 42 | /**< allows outside methods to use typename F without knowing what it is */ 43 | pool_(unsigned short); 44 | /**< constructor */ 45 | virtual ~pool_(); 46 | /**< destructor */ 47 | F* from_pool(); 48 | /**< removes a typename F from the pool and returns it */ 49 | void to_pool(F*); 50 | /**< pushes a new typename F pointer to the pool, reseting it */ 51 | F* copy(const F&); 52 | /**< removes a typename F pointer from the pool, copies the input 53 | into it, and returns it */ 54 | }; // closes template pool_ 55 | 56 | //template const unsigned short pool_::_init_size = 5000; 57 | /* initialization size for the pool */ 58 | 59 | template pool_::pool_(unsigned short siz) 60 | : _vec(siz, 0) { 61 | for (int i = 0; i != siz; ++i) { 62 | _vec[i] = new F(); 63 | } 64 | } 65 | /* constructor */ 66 | 67 | template pool_::~pool_() { 68 | for (int i = 0; i != _vec.size(); ++i) { 69 | delete _vec[i]; 70 | } 71 | } 72 | /* destructor */ 73 | 74 | template F* pool_::from_pool() { 75 | if (_vec.size() != 0) { // pool not empty 76 | F* result = _vec.back(); 77 | _vec.pop_back(); 78 | return result; 79 | } 80 | else { 81 | return new F(); 82 | } 83 | } 84 | /* removes a typename F from the pool and returns it */ 85 | 86 | template void pool_::to_pool(F* pF) { 87 | pF->reset(); 88 | _vec.push_back(pF); 89 | } 90 | /* pushes a new typename F pointer to the pool, reseting it */ 91 | 92 | template F* pool_::copy(const F& oF) { 93 | F* result = from_pool(); 94 | *result = oF; 95 | return result; 96 | } 97 | /* removes a typename F pointer from the pool, copies the input 98 | into it, and returns it */ 99 | 100 | } // closes namespace math 101 | 102 | #endif 103 | -------------------------------------------------------------------------------- /project_phd/phd/math/templates/singleton_holder_.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_SINGLETON_HOLDER 2 | #define MATH_SINGLETON_HOLDER 3 | 4 | #include "../math.h" 5 | #include 6 | 7 | /* 8 | This file implementes the singleton holder template, useful to transform any 9 | other class T in a singleton. 10 | 11 | MODE OF USE: 12 | The singleton holder shall be a friend of the singleton T, which shall have a 13 | public destructor, a private empty constructor (accesible to the singleton 14 | holder as it is a friend), and forbidden copy constructor and assignment 15 | operators. The singleton T shall also include a singleton holder private 16 | attribute as "typedef math::singleton_holder_ _instance" and a public 17 | get_instance() method to provide access to it containing 18 | "return _instance::get_instance()". 19 | */ 20 | 21 | namespace math { 22 | 23 | template class singleton_holder_ { 24 | private: 25 | static boost::scoped_ptr _instance; 26 | /**< smart pointer to type */ 27 | singleton_holder_(); 28 | /**< empty constructor not implemented */ 29 | singleton_holder_(const singleton_holder_&); 30 | /**< copy constructor not implemented */ 31 | singleton_holder_& operator=(const singleton_holder_&); 32 | /**< overloaded operator = (assignment) not implemented */ 33 | ~singleton_holder_() { 34 | } 35 | /**< destructor not implemented */ 36 | public: 37 | typedef T type; 38 | /**< allows outside methods to use typename T without knowing what it is */ 39 | inline static T& get_instance() { 40 | if (_instance.get() == 0) { 41 | _instance.reset(new T); 42 | } 43 | return *_instance; 44 | } 45 | /**< return reference to single instance */ 46 | }; // closes class singleton 47 | 48 | template 49 | boost::scoped_ptr singleton_holder_::_instance; 50 | } 51 | 52 | // closes namespace math 53 | 54 | #endif 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/algorithm.cpp: -------------------------------------------------------------------------------- 1 | #include "algorithm.h" 2 | #include "vec.h" 3 | 4 | bool math::check_range(const double& op1, const double& op2, const double& opX, bool& flag) { 5 | if (op1 > opX) {flag = false; return false;} 6 | if (op2 < opX) {flag = true; return false;} 7 | return true; 8 | } 9 | /* checks if the input magnitude opX is within the range defined by the op1 10 | and op2 input2, assumming that op2 is higher than op1. If yes, returns true and 11 | flag is meaningless. If not, returns false and flag is true if above higher margin, 12 | false if below lower margin. */ 13 | 14 | int math::search_binary(const double& op1, const math::vec& vec) { 15 | return upper_bound(vec.begin(), vec.end(), op1) - vec.begin() - 1; 16 | } 17 | /* For op1, and given an input vector of magnitudes, it 18 | returns an integer locating the latest position in the vector that is smaller 19 | OR equal to op1. For a size "n" vector, the response range is 20 | [-1,n-1]. If -1, it means magnitude is less than first (0) vector magnitude. 21 | If "n-1" (vector size), it means magnitude is higher or equal than last (n-1) 22 | vector magnitude. Only overloaded for longitudes and bearings, in which the 23 | range is [0,n-1], as being located before the first is analogous to after the 24 | last. */ 25 | 26 | int math::search_equispaced(const double& op1, const math::vec& vec, 27 | const double& Odiff) { 28 | return std::max(std::min((int) floor((op1 - vec[0]) / Odiff), vec.size() - 1), -1); 29 | } 30 | /* For op1, and given an input vector of magnitudes and 31 | the difference between consecutive members of the vector, it returns an integer 32 | locating the latest position in the vector that is smaller OR equal to the 33 | op1. For a size "n" vector, the response range is [-1,n-1]. If -1, it 34 | means magnitude is less than first (0) vector magnitude. If "n-1" (vector size), 35 | it means magnitude is higher or equal than last (n-1) vector magnitude. Only 36 | overloaded for longitudes and bearings, in which the range is [0,n-1], as being 37 | located before the first is analogous to after the last. */ 38 | 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/algorithm.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_ALGORITHM 2 | #define MATH_ALGORITHM 3 | 4 | #include "../math.h" 5 | #include "../logic/constant.h" 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | namespace math { 12 | 13 | class vec; // used before it is defined 14 | 15 | MATH_API 16 | bool check_range(const double& op1, const double& op2, const double& opX, bool& flag); 17 | /**< checks if the input magnitude opX is within the range defined by the op1 18 | and op2 input2, assumming that op2 is higher than op1. If yes, returns true and 19 | flag is meaningless. If not, returns false and flag is true if above higher margin, 20 | false if below lower margin. */ 21 | 22 | MATH_API 23 | int search_binary(const double& op1, const math::vec& vec); 24 | /**< For op1, and given an input vector of magnitudes, it 25 | returns an integer locating the latest position in the vector that is smaller 26 | OR equal to op1. For a size "n" vector, the response range is 27 | [-1,n-1]. If -1, it means magnitude is less than first (0) vector magnitude. 28 | If "n-1" (vector size), it means magnitude is higher or equal than last (n-1) 29 | vector magnitude. Only overloaded for longitudes and bearings, in which the 30 | range is [0,n-1], as being located before the first is analogous to after the 31 | last. */ 32 | 33 | MATH_API 34 | int search_equispaced(const double& op1, const math::vec& vec, const double& diff); 35 | /**< For op1, and given an input vector of magnitudes and 36 | the difference between consecutive members of the vector, it returns an integer 37 | locating the latest position in the vector that is smaller OR equal to the 38 | op1. For a size "n" vector, the response range is [-1,n-1]. If -1, it 39 | means magnitude is less than first (0) vector magnitude. If "n-1" (vector size), 40 | it means magnitude is higher or equal than last (n-1) vector magnitude. Only 41 | overloaded for longitudes and bearings, in which the range is [0,n-1], as being 42 | located before the first is analogous to after the last. */ 43 | 44 | } // closes namespace math 45 | 46 | #endif 47 | 48 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/classifiers.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_MAG_CLASSIFIERS_H 2 | #define MATH_MAG_CLASSIFIERS_H 3 | #include "../interp/interp.h" 4 | 5 | #endif 6 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/vec.cpp: -------------------------------------------------------------------------------- 1 | #include "vec.h" 2 | 3 | // CLASS VEC 4 | // ========= 5 | // ========= 6 | 7 | math::vec::vec(int siz) 8 | : _vec(siz) { 9 | } 10 | /* constructor based on vector size */ 11 | 12 | math::vec::vec(const vec& other) 13 | : _vec(other._vec.size()) { 14 | for (int i = 0; i != other._vec.size(); ++i) { 15 | if (other._vec[i] != 0) { 16 | _vec[i] = other._vec[i]; 17 | } 18 | else _vec[i] = 0; 19 | } 20 | } 21 | /* copy constructor */ 22 | 23 | math::vec::~vec() { 24 | } 25 | /* destructor */ 26 | 27 | bool math::vec::operator==(const vec& op2) const { 28 | if (_vec.size() != op2._vec.size()) {return false;} 29 | for (int i = 0; i != _vec.size(); ++i) { 30 | if (_vec[i] != op2._vec[i]) {return false;} 31 | } 32 | return true; 33 | } 34 | /* overloaded operator == (equal) */ 35 | 36 | std::vector::const_iterator math::vec::begin() const { 37 | return _vec.begin(); 38 | } 39 | /* returns constant iterator to the first magnitude pointer */ 40 | 41 | std::vector::const_iterator math::vec::end() const { 42 | return _vec.end(); 43 | } 44 | /* returns constant iterator to the last magnitude pointer */ 45 | 46 | const double& math::vec::front() const { 47 | return _vec.front(); 48 | } 49 | double& math::vec::front() { 50 | return _vec.front(); 51 | } 52 | /* returns reference to first element */ 53 | 54 | const double& math::vec::back() const { 55 | return _vec.back(); 56 | } 57 | double& math::vec::back() { 58 | return _vec.back(); 59 | } 60 | /* returns reference to last element */ 61 | 62 | double math::vec::diff (int siz1, int siz2) const { 63 | return (_vec[siz1] - _vec[siz2]); 64 | } 65 | /* obtains the shortest numeric difference between the magnitudes 66 | positioned in pos1 and pos2. */ 67 | 68 | const double& math::vec::operator[](int index1) const { 69 | return _vec[index1]; 70 | } 71 | double& math::vec::operator[](int index1) { 72 | return _vec[index1]; 73 | } 74 | /* get a magnitude reference from the position provided by index1 */ 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/vec.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_VEC 2 | #define MATH_VEC 3 | 4 | #include "../math.h" 5 | #include "algorithm.h" 6 | #include "../interp/ratio.h" 7 | #include 8 | #include 9 | 10 | /* 11 | This file contains the virtual class vec, intended to contain multidimensional vectors. 12 | */ 13 | 14 | namespace math { 15 | 16 | // CLASS VEC 17 | // ========= 18 | // ========= 19 | 20 | class MATH_API vec { 21 | protected: 22 | std::vector _vec; 23 | /**< vector of pointer to magnitude objects */ 24 | 25 | vec(); 26 | /**< empty constructor not implemented*/ 27 | vec(int siz); 28 | /**< constructor based on vector size */ 29 | vec(const vec&); 30 | /**< copy constructor */ 31 | vec& operator=(const vec& op2); 32 | /**< overloaded operator = (assignment) not implemented */ 33 | public: 34 | virtual ~vec(); 35 | /**< destructor */ 36 | virtual bool operator==(const vec& op2) const; 37 | /**< overloaded operator == (equal) */ 38 | virtual bool operator!=(const vec& op2) const {return !(*this == op2);} 39 | /**< overloaded operator != (not equal) */ 40 | 41 | virtual const int size() const {return _vec.size();} 42 | /**< returns vector size */ 43 | 44 | virtual std::vector::const_iterator begin() const; 45 | /**< returns constant iterator to the first magnitude pointer */ 46 | virtual std::vector::const_iterator end() const; 47 | /**< returns constant iterator to the last magnitude pointer */ 48 | 49 | virtual const double& front() const; 50 | virtual double& front(); 51 | /**< returns reference to first element */ 52 | virtual const double& back() const; 53 | virtual double& back(); 54 | /**< returns reference to last element */ 55 | 56 | const double& operator[](int index1) const; 57 | double& operator[](int index1); 58 | /**< get a magnitude reference from the position provided by index1 */ 59 | 60 | virtual double diff (int siz1, int siz2) const; 61 | /**< obtains the shortest numeric difference between the magnitudes 62 | positioned in pos1 and pos2. */ 63 | }; // closes class vec 64 | 65 | } // closes namespace math 66 | 67 | #endif 68 | 69 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/vec1.cpp: -------------------------------------------------------------------------------- 1 | #include "vec1.h" 2 | 3 | // CLASS MAGV1 (unidimensional vector of mag pointers) 4 | // =================================================== 5 | // =================================================== 6 | 7 | math::vec1::vec1() : vec(0), _siz1(0) { 8 | } 9 | /* empty constructor creates vector of size 0 */ 10 | 11 | math::vec1::vec1(unsigned int siz1) : vec(siz1), _siz1(siz1) { 12 | for (unsigned int i = 0; i != _siz1; ++i) { 13 | _vec[i] = 0.; 14 | } 15 | } 16 | /* constructor based on vector size */ 17 | 18 | math::vec1::vec1(const std::string& st) : vec(0), _siz1(0) { 19 | std::ifstream mystream(st.c_str()); 20 | create(mystream, st); 21 | mystream.close(); 22 | } 23 | /* constructor based on a string identifying a text file containing the 24 | required info. The first number contains the size of the vector, followed 25 | by its contents in standard units. */ 26 | 27 | math::vec1::vec1(std::ifstream& mystream) : vec(0), _siz1(0) { 28 | create(mystream, ""); 29 | } 30 | /* constructor based on an open stream containing the required info. 31 | The first number contains the size of the vector, followed by its contents 32 | in standard units. Name of the text file containing the info is optional*/ 33 | 34 | math::vec1::vec1(const vec1& other) 35 | : vec(other), _siz1(other._siz1) { 36 | } 37 | /* copy constructor */ 38 | 39 | math::vec1& math::vec1::operator=(const vec1& op2) { 40 | _siz1 = op2._siz1; 41 | _vec = std::vector(_siz1); 42 | for (unsigned int i = 0; i != _siz1 ; ++i) { 43 | _vec[i] = op2._vec[i]; 44 | } 45 | return *this; 46 | } 47 | /* overloaded operator = (assignment) */ 48 | 49 | math::vec1::~vec1() {} 50 | /* destructor */ 51 | 52 | bool math::vec1::operator==(const vec1& op2) const { 53 | return (static_cast(*this) == static_cast(op2)); 54 | } 55 | /* overloaded operator == (equal) */ 56 | 57 | math::vec1* math::vec1::create(unsigned int siz) { 58 | return new vec1(siz); 59 | } 60 | /* returns default altitude vector pointer (for magnitude factory) */ 61 | 62 | void math::vec1::set(unsigned int index, double value) { 63 | _vec[index] = value; 64 | } 65 | /* change the value in [m] in the position provided by siz */ 66 | 67 | /* ===== ===== Private Methods ===== ===== */ 68 | void math::vec1::create(std::ifstream& mystream, const std::string& st) { 69 | // do not replace by unsigned short as it does not work if text file has decimals for 70 | // the sizes, as in 3.0 instead of 3. 71 | double siz = 0; 72 | mystream >> siz; 73 | _siz1 = siz; 74 | _vec = std::vector(siz); 75 | double temp = 0.; 76 | for (unsigned int i = 0; i != siz; ++i) { 77 | mystream >> temp; 78 | _vec[i] = temp; 79 | } 80 | } 81 | /* initialization based on an open stream containing the required info. 82 | The first number contains the size of the vector, followed by its contents 83 | in standard units. Name of the text file containing the info is optional*/ 84 | 85 | 86 | 87 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/vec1.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_VEC1 2 | #define MATH_VEC1 3 | 4 | #include "../math.h" 5 | #include "vec.h" 6 | 7 | /* 8 | This file contains the virtual class vec1, intended to contain unidimensional 9 | vectors. 10 | */ 11 | 12 | namespace math { 13 | 14 | // CLASS VEC1 (unidimensional vector) 15 | // ================================== 16 | // ================================== 17 | 18 | class MATH_API vec1: public vec { 19 | protected: 20 | int _siz1; 21 | /**< size in 1st dimension */ 22 | 23 | void create(std::ifstream& mystream, const std::string& st); 24 | /**< initialization based on an open stream containing the required info. 25 | The first number contains the size of the vector, followed by its contents 26 | in standard units. Name of the text file containing the info is optional*/ 27 | public: 28 | vec1(); 29 | /**< empty constructor */ 30 | vec1(unsigned int siz1); 31 | /**< constructor based on vector size */ 32 | vec1(const std::string& st); 33 | /**< constructor based on a string identifying a text file containing the 34 | required info. The first number contains the size of the vector, followed 35 | by its contents in standard units. */ 36 | vec1(std::ifstream& mystream); 37 | /**< constructor based on an open stream containing the required info. 38 | The first number contains the size of the vector, followed by its contents 39 | in standard units. Name of the text file containing the info is optional*/ 40 | vec1(const vec1&); 41 | /**< copy constructor */ 42 | vec1& operator=(const vec1& op2); 43 | /**< overloaded operator = (assignment) */ 44 | ~vec1(); 45 | /**< destructor */ 46 | bool operator==(const vec1& op2) const; 47 | /**< overloaded operator == (equal) */ 48 | bool operator!=(const vec1& op2) const {return !(*this == op2);} 49 | /**< overloaded operator != (not equal) */ 50 | vec1* clone() const {return new vec1(*this);}; 51 | /**< cloner */ 52 | static vec1* create(unsigned int siz); 53 | /**< returns default F vector pointer (for magnitude factory) */ 54 | 55 | void set(unsigned int index, double value); 56 | /**< change the value in [m] in the position provided by siz */ 57 | const int size1() const {return _siz1;} 58 | /**< returns vector size */ 59 | const double& operator[](unsigned int index1) const {return _vec[index1];} 60 | double& operator[](unsigned int index1) {return _vec[index1];} 61 | /**< get a magnitude reference from the position provided by index1 */ 62 | const double& get(unsigned int index1) const {return _vec[index1];} 63 | double& get(unsigned int index1) {return _vec[index1];} 64 | /**< get a magnitude reference from the position provided by index1 */ 65 | }; // closes class vec1 66 | 67 | } // closes namespace math 68 | 69 | inline std::ostream& operator<<(std::ostream& stream, 70 | const math::vec1& Ovec1) { 71 | stream << "size " << Ovec1.size1() << " vector of " << " magnitudes";; 72 | return stream; 73 | } 74 | /**< overloaded operator << (inserter): no need for friend of class vec1 as it 75 | does not use private members of mag. */ 76 | 77 | #endif 78 | 79 | -------------------------------------------------------------------------------- /project_phd/phd/math/vec/vec2.h: -------------------------------------------------------------------------------- 1 | #ifndef MATH_VEC2 2 | #define MATH_VEC2 3 | 4 | #include "../math.h" 5 | #include "vec1.h" 6 | 7 | /* 8 | This file contains the virtual class vec2, intended to contain bidimensional 9 | vectors. 10 | */ 11 | 12 | namespace math { 13 | 14 | // CLASS VEC2 (bidimensional vector) 15 | // ================================= 16 | // ================================= 17 | 18 | class MATH_API vec2: public vec { 19 | protected: 20 | int _siz1; 21 | /**< size in 1st dimension */ 22 | int _siz2; 23 | /**< size in 2nd dimension */ 24 | 25 | void create(std::ifstream& mystream, const std::string& st); 26 | /**< initialization based on an open stream containing the required info. 27 | The first number contains the size of each vector and the second the 28 | number of vectors, followed by its contents in standard units. 29 | Name of the text file containing the info is optional*/ 30 | void create_bis(std::ifstream& mystream); 31 | /**< initialization based on an open stream containing the contents 32 | * in standard units (without the sizes first, as above). */ 33 | public: 34 | vec2(); 35 | /**< empty constructor */ 36 | vec2(unsigned int siz1, unsigned intsiz2); 37 | /**< constructor based on matrix dimensions */ 38 | vec2(const vec2&); 39 | /**< copy constructor */ 40 | vec2(const std::string& st); 41 | /**< constructor based on a string identifying a text file containing the 42 | required info. The first number contains the size of each vector and the 43 | second the number of vectors, followed by its contents in standard units. */ 44 | vec2(std::ifstream& mystream); 45 | /**< constructor based on an open stream containing the required info. 46 | The first number contains the size of each vector and the second the 47 | number of vectors, followed by its contents in standard units. 48 | Name of the text file containing the info is optional*/ 49 | vec2(unsigned int siz1, unsigned int siz2, std::ifstream &mystream); 50 | /**< constructor based on matrix sizes and input stream containing data */ 51 | vec2& operator=(const vec2& op2); 52 | /**< overloaded operator = (assignment) */ 53 | ~vec2(); 54 | /**< destructor */ 55 | bool operator==(const vec2& op2) const; 56 | /**< overloaded operator == (equal) */ 57 | bool operator!=(const vec2& op2) const {return !(*this == op2);} 58 | /**< overloaded operator != (not equal) */ 59 | vec2* clone() const {return new vec2(*this);} 60 | /**< cloner */ 61 | math::vec1* sample_vector() const {return new math::vec1(this->size());} 62 | /**< returns pointer of magnitude vector of proper type and size n */ 63 | 64 | void set(unsigned int index1, unsigned int index2, double value); 65 | /**< change the value in standard units in the position provided by 66 | index1 and index2 */ 67 | const int size1() const {return _siz1;} 68 | const int size2() const {return _siz2;} 69 | /**< returns size in different dimensions */ 70 | int index(unsigned int index1, unsigned int index2) const 71 | {return _siz1 * index2 + index1;} 72 | /**< returns position within vec of combination of two inputs */ 73 | const double& get(unsigned int index1, unsigned int index2) const {return _vec[_siz1 * index2 + index1];} 74 | double& get(unsigned int index1, unsigned int index2) {return _vec[_siz1 * index2 + index1];} 75 | /**< get a magnitude reference from the positions provided by index1 and index2 */ 76 | }; // closes class vec2 77 | 78 | } // closes namespace math 79 | 80 | #endif 81 | 82 | -------------------------------------------------------------------------------- /project_phd/phd/nav/air/filter_air.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_FILTER_AIR 2 | #define NAV_FILTER_AIR 3 | 4 | #include "../nav.h" 5 | #include "../kalman/ekf_handler_.h" 6 | #include "acft/st/trj_nav_in.h" 7 | #include "acft/st/trj_nav_out.h" 8 | #include "acft/st/trj_sens_in.h" 9 | #include "acft/st/trj_sens_out.h" 10 | #include "acft/st/trj_truth.h" 11 | #include "acft/sens/suite.h" 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | namespace nav { 18 | 19 | ////////////////////////////////////////////////////////////////////////////////// 20 | ////////////////////////////////////////////////////////////////////////////////// 21 | 22 | // CLASS FILTER AIR 23 | // ================ 24 | // ================ 25 | 26 | class NAV_API filter_air { 27 | protected: 28 | /**< weak pointer to sensor suite */ 29 | const sens::suite* const _Psuite; 30 | 31 | public: 32 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 33 | /**< constructor based on suite of sensors */ 34 | filter_air(const sens::suite& Osuite) : _Psuite(&Osuite) {} 35 | /**< default constructor */ 36 | filter_air() = delete; 37 | /**< copy constructor */ 38 | filter_air(const filter_air&) = delete; 39 | /**< move constructor */ 40 | filter_air(filter_air&&) = delete; 41 | /**< destructor */ 42 | virtual ~filter_air() = default; 43 | /**< copy assignment */ 44 | filter_air& operator=(const filter_air&) = delete; 45 | /**< move assignment */ 46 | filter_air& operator=(filter_air&&) = delete; 47 | 48 | /**< complete constructor with navigation time and size of navigation vector, which are not available at construction time */ 49 | virtual void finalize_constructor(const double& Deltat_sec_nav, const unsigned int& nel_nav) = 0; 50 | /**< initialize filter filling up the initial navigation output state vector Ost_nav_out_init, based on the initial sensors output state vector Ost_sens_out_init, 51 | * and the initial navigation input state vector Ost_nav_in_init (for filter evaluation purposes only). */ 52 | virtual void initialize(st::st_nav_out& Ost_nav_out_init, const st::st_sens_out& Ost_sens_out_init, const st::st_nav_in& Ost_nav_in) = 0; 53 | /**< execute filter step filling up the navigation output state vector Ost_nav_out, based on the sensors output state vector Ost_sens_out, the navigation input 54 | * state vector Ost_nav_in (for filter evaluation purposes only), and the current navigation trajectory vector position. */ 55 | virtual void execute_step(st::st_nav_out& Ost_nav_out, const st::st_sens_out& Ost_sens_out, const st::st_nav_in& Ost_nav_in, const unsigned int& s) = 0; 56 | /**< resize of all filter components to input size */ 57 | virtual void resize(const unsigned long& nel) = 0; 58 | /**< returns size of all filter components */ 59 | virtual unsigned long get_size() const = 0; 60 | 61 | 62 | 63 | /**< creates text files describing the filter performance */ 64 | virtual void textplot(const boost::filesystem::path& path_folder, const st::trj_sens_in& Otrj_sens_in, const st::trj_sens_out& Otrj_sens_out, const st::trj_nav_in& Otrj_nav_in, const st::trj_nav_out& Otrj_nav_out) const = 0; 65 | 66 | 67 | }; // closes class filter_air 68 | 69 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 70 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 71 | 72 | }; // closes namespace nav 73 | 74 | #endif 75 | -------------------------------------------------------------------------------- /project_phd/phd/nav/init/error_gen_att.cpp: -------------------------------------------------------------------------------- 1 | #include "error_gen_att.h" 2 | #include "math/logic/constant.h" 3 | #include "ang/rotate/rotv.h" 4 | #include 5 | #include 6 | 7 | // CLASS ERROR_GENERATOR_ATTITUDE 8 | // ============================== 9 | // ============================== 10 | 11 | nav::error_gen_att::error_gen_att(const double& sigma_deg, const int& seed) 12 | : _sigma_deg(sigma_deg), _gen(seed), _dist_normal(0.,1.), _dist_uniform(-179, 180) { 13 | 14 | double gamma_rad = _sigma_deg * math::constant::D2R() * _dist_normal(_gen); 15 | double phi1_rad = _dist_uniform(_gen) * math::constant::D2R(); // phi1 [-179,180] 16 | double phi2_rad = _dist_uniform(_gen) * math::constant::D2R() / 2; // phi2 [-90,+90] 17 | ang::rotv rv(Eigen::Vector3d(cos(phi1_rad) * cos(phi2_rad), sin(phi2_rad), sin(phi1_rad)), gamma_rad); 18 | _q_res = rv; 19 | } 20 | /* constructor based on rotation size standard deviation and seed */ 21 | 22 | const ang::rodrigues& nav::error_gen_att::eval() const { 23 | return _q_res; 24 | } 25 | /* return quaternion */ 26 | 27 | nav::error_gen_att* nav::error_gen_att::create_init_eul_error_generator(nav::logic::INITEUL_ID initeul_id, const int& seed) { 28 | nav::error_gen_att* Pres = nullptr; 29 | switch(initeul_id) { 30 | case nav::logic::initeul_id_zero: 31 | Pres = new nav::error_gen_att(0., seed); 32 | break; 33 | case nav::logic::initeul_id_base: 34 | Pres = new nav::error_gen_att(0.1, seed); // 0.1 deg in rotation vector 35 | break; 36 | case nav::logic::initeul_id_better: 37 | Pres = new nav::error_gen_att(0.05, seed); // 0.05 deg in rotation vector 38 | break; 39 | case nav::logic::initeul_id_worse: 40 | Pres = new nav::error_gen_att(0.2, seed); // 0.2 deg in rotation vector 41 | break; 42 | case nav::logic::initeul_id_worst: 43 | Pres = new nav::error_gen_att(0.5, seed); // 0.5 deg in rotation vector 44 | break; 45 | case nav::logic::initeul_size: 46 | throw std::runtime_error("Initial Euler angles error generator model not available"); 47 | default: 48 | throw std::runtime_error("Initial euler angles error generator model not available"); 49 | } 50 | return Pres; 51 | } 52 | /* create initial Euler angle error generator */ 53 | 54 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 55 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | -------------------------------------------------------------------------------- /project_phd/phd/nav/init/error_gen_att.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_ERROR_GEN_ATT 2 | #define NAV_ERROR_GEN_ATT 3 | 4 | #include "../nav.h" 5 | #include "logic.h" 6 | #include "ang/rotate/rodrigues.h" 7 | 8 | #include 9 | #include 10 | #include 11 | 12 | namespace nav { 13 | 14 | // CLASS ERROR_GENERATOR_ATTITUDE 15 | // ============================== 16 | // ============================== 17 | 18 | class NAV_API error_gen_att { 19 | private: 20 | /**< rotation size standard deviation [deg] */ 21 | double _sigma_deg; 22 | /**< seed generator */ 23 | std::ranlux24_base _gen; 24 | /**< standard normal distribution */ 25 | std::normal_distribution _dist_normal; 26 | /**< uniform integer distribution */ 27 | std::uniform_int_distribution _dist_uniform; 28 | 29 | /**< evaluation result, so it can be retrieved multiple times */ 30 | ang::rodrigues _q_res; 31 | public: 32 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 33 | 34 | /**< default constructor */ 35 | error_gen_att() = delete; 36 | /**< constructor based on rotation size standard deviation and seed */ 37 | error_gen_att(const double& sigma_deg, const int& seed); 38 | /**< copy constructor */ 39 | error_gen_att(const error_gen_att&) = delete; 40 | /**< move constructor */ 41 | error_gen_att(error_gen_att&&) = delete; 42 | /**< destructor */ 43 | ~error_gen_att() = default; 44 | /**< copy assignment */ 45 | error_gen_att& operator=(const error_gen_att&) = delete; 46 | /**< move assignment */ 47 | error_gen_att& operator=(error_gen_att&&) = delete; 48 | 49 | /**< return quaternion */ 50 | const ang::rodrigues& eval() const; 51 | 52 | /**< create initial Euler angle error generator */ 53 | static nav::error_gen_att* create_init_eul_error_generator(nav::logic::INITEUL_ID, const int& seed); 54 | 55 | /**< get rotation size standard deviation [deg] to read */ 56 | const double& get_sigma_deg() const {return _sigma_deg;} 57 | }; // closes class error_gen_att 58 | 59 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 60 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 61 | 62 | }; // closes namespace nav 63 | 64 | #endif 65 | -------------------------------------------------------------------------------- /project_phd/phd/nav/init/error_gen_triple.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_ERROR_GEN_TRIPLE 2 | #define NAV_ERROR_GEN_TRIPLE 3 | 4 | #include "../nav.h" 5 | #include "logic.h" 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | namespace nav { 12 | 13 | // CLASS ERROR_GENERATOR_TRIPLE 14 | // ============================ 15 | // ============================ 16 | 17 | class NAV_API error_gen_triple { 18 | private: 19 | /**< white noise [unit] */ 20 | double _sigma; 21 | /**< seed generator */ 22 | std::ranlux24_base _gen; 23 | /**< standard normal distribution */ 24 | std::normal_distribution _dist; 25 | 26 | /**< evaluation result, so it can be retrieved multiple times */ 27 | Eigen::Vector3d _res; 28 | public: 29 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 30 | 31 | /**< default constructor */ 32 | error_gen_triple() = delete; 33 | /**< constructor based on white noise and seed */ 34 | error_gen_triple(const double& sigma, const int& seed); 35 | /**< copy constructor */ 36 | error_gen_triple(const error_gen_triple&) = delete; 37 | /**< move constructor */ 38 | error_gen_triple(error_gen_triple&&) = delete; 39 | /**< destructor */ 40 | ~error_gen_triple() = default; 41 | /**< copy assignment */ 42 | error_gen_triple& operator=(const error_gen_triple&) = delete; 43 | /**< move assignment */ 44 | error_gen_triple& operator=(error_gen_triple&&) = delete; 45 | 46 | /**< return sensor measurement */ 47 | const Eigen::Vector3d& eval() const; 48 | 49 | /**< create initial accelerometer error generator */ 50 | static nav::error_gen_triple* create_init_acc_error_generator(nav::logic::INITACC_ID, const int& seed); 51 | /**< create initial gyroscope error generator */ 52 | static nav::error_gen_triple* create_init_gyr_error_generator(nav::logic::INITGYR_ID, const int& seed); 53 | /**< create initial magnetometer error generator */ 54 | static nav::error_gen_triple* create_init_mag_error_generator(nav::logic::INITMAG_ID, const int& seed); 55 | /**< create initial NED magnetic field error generator */ 56 | static nav::error_gen_triple* create_init_mgn_error_generator(nav::logic::INITMGN_ID, const int& seed); 57 | 58 | /**< get white noise [unit] to read */ 59 | const double& get_sigma() const {return _sigma;} 60 | }; // closes class error_gen_triple 61 | 62 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 63 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////// 64 | 65 | }; // closes namespace nav 66 | 67 | #endif 68 | -------------------------------------------------------------------------------- /project_phd/phd/nav/init/init_error.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_INIT_ERROR 2 | #define NAV_INIT_ERROR 3 | 4 | #include "../nav.h" 5 | #include "error_gen_triple.h" 6 | #include "error_gen_att.h" 7 | #include "math/logic/seeder.h" 8 | #include "acft/st/sti.h" 9 | #include "acft/st/trj_sens_out.h" 10 | 11 | namespace nav { 12 | 13 | // CLASS INIT_ERROR 14 | // ================ 15 | // ================ 16 | 17 | class NAV_API init_error { 18 | private: 19 | /**< pointer to initial Euler angles error generator */ 20 | nav::error_gen_att* _Piniterr_eul; 21 | /**< pointer to initial accelerometer error generator */ 22 | nav::error_gen_triple* _Piniterr_acc; 23 | /**< pointer to initial gyroscope error generator */ 24 | nav::error_gen_triple* _Piniterr_gyr; 25 | /**< pointer to initial magnetometer error generator */ 26 | nav::error_gen_triple* _Piniterr_mag; 27 | /**< pointer to initial NED magnetic field error generator */ 28 | nav::error_gen_triple* _Piniterr_mgn; 29 | public: 30 | EIGEN_MAKE_ALIGNED_OPERATOR_NEW 31 | 32 | /**< default constructor */ 33 | init_error() = delete; 34 | /**< constructor based on seed order and identifiers */ 35 | init_error(math::seeder& Oseeder, 36 | nav::logic::INITEUL_ID initeul_id, nav::logic::INITACC_ID initacc_id, nav::logic::INITGYR_ID initgyr_id, 37 | nav::logic::INITMAG_ID initmag_id, nav::logic::INITMGN_ID initmgn_id); 38 | /**< copy constructor */ 39 | init_error(const init_error&) = delete; 40 | /**< move constructor */ 41 | init_error(init_error&&) = delete; 42 | /**< destructor */ 43 | ~init_error(); 44 | /**< copy assignment */ 45 | init_error& operator=(const init_error&) = delete; 46 | /**< move assignment */ 47 | init_error& operator=(init_error&&) = delete; 48 | 49 | /**< fills up the initial estimated aircraft attitude based on the initial conditions, 50 | * and writes results in input stream */ 51 | void eval_eul(const st::sti& Osti, ang::rodrigues& q_nb_init, std::ostream& Ostream) const; 52 | /**< fills up the initial estimated full accelerometer error based on the initial conditions, 53 | * and writes the results in input stream */ 54 | void eval_acc(const st::st_sens_out& Ost_sens_out_ini, Eigen::Vector3d& Eacc_init_std_mps2, Eigen::Vector3d& Eacc_init_mps2, std::ostream& Ostream) const; 55 | /**< fills up the initial estimated full gyroscope error based on the initial conditions, 56 | * and writes the results in input stream */ 57 | void eval_gyr(const st::st_sens_out& Ost_sens_out_ini, Eigen::Vector3d& Egyr_init_std_rps, Eigen::Vector3d& Egyr_init_rps, std::ostream& Ostream) const; 58 | /**< fills up the initial estimated full magnetometer error based on the initial conditions, 59 | * and writes the results in input stream */ 60 | void eval_mag(const st::st_sens_out& Ost_sens_out_ini, Eigen::Vector3d& Emag_init_std_nT, Eigen::Vector3d& Emag_init_nT, std::ostream& Ostream) const; 61 | /**< fills up the initial estimated difference of the magnetic field between the models are reality 62 | * based on the initial conditions, and writes results in input stream */ 63 | void eval_mgn(const st::sti& Osti, const env::earth& Oearth, Eigen::Vector3d& Berror_init_std_nT, Eigen::Vector3d& Berror_init_nT, std::ostream& Ostream) const; 64 | 65 | }; // closes class init_error 66 | 67 | }; // closes namespace nav 68 | 69 | #endif 70 | 71 | 72 | -------------------------------------------------------------------------------- /project_phd/phd/nav/init/logic.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_MOTION_LOGIC 2 | #define NAV_MOTION_LOGIC 3 | 4 | #include "../nav.h" 5 | 6 | namespace nav { 7 | namespace logic { 8 | /**< Enumeration that contains the different initial Euler angle error generators */ 9 | enum INITEUL_ID { 10 | initeul_id_zero = 0, 11 | initeul_id_base = 1, 12 | initeul_id_better = 2, 13 | initeul_id_worse = 3, 14 | initeul_id_worst = 4, 15 | initeul_size = 5 16 | }; 17 | /**< Enumeration that contains the different initial accelerometer error generators */ 18 | enum INITACC_ID { 19 | initacc_id_zero = 0, 20 | initacc_id_base = 1, 21 | initacc_id_worse = 2, 22 | initacc_id_worst = 3, 23 | initacc_size = 4 24 | }; 25 | /**< Enumeration that contains the different initial gyroscope error generators */ 26 | enum INITGYR_ID { 27 | initgyr_id_zero = 0, 28 | initgyr_id_base = 1, 29 | initgyr_id_worse = 2, 30 | initgyr_id_worst = 3, 31 | initgyr_size = 4 32 | }; 33 | /**< Enumeration that contains the different initial magnetometer error generators */ 34 | enum INITMAG_ID { 35 | initmag_id_zero = 0, 36 | initmag_id_base = 1, 37 | initmag_id_worse = 2, 38 | initmag_id_worst = 3, 39 | initmag_size = 4 40 | }; 41 | /**< Enumeration that contains the different initial NED magnetic field error generators */ 42 | enum INITMGN_ID { 43 | initmgn_id_zero = 0, 44 | initmgn_id_base = 1, 45 | initmgn_id_worse = 2, 46 | initmgn_id_worst = 3, 47 | initmgn_size = 4 48 | }; 49 | } // closes namespace logic 50 | }; // closes namespace nav 51 | 52 | #endif 53 | -------------------------------------------------------------------------------- /project_phd/phd/nav/nav.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // Generic helper definitions for shared library support 4 | #if defined _WIN32 || defined __CYGWIN__ 5 | #define NAV_HELPER_DLL_IMPORT __declspec(dllimport) 6 | #define NAV_HELPER_DLL_EXPORT __declspec(dllexport) 7 | #define NAV_HELPER_DLL_LOCAL 8 | #else 9 | #if __GNUC__ >= 4 10 | #define NAV_HELPER_DLL_IMPORT __attribute__ ((visibility ("default"))) 11 | #define NAV_HELPER_DLL_EXPORT __attribute__ ((visibility ("default"))) 12 | #define NAV_HELPER_DLL_LOCAL __attribute__ ((visibility ("hidden"))) 13 | #else 14 | #define NAV_HELPER_DLL_IMPORT 15 | #define NAV_HELPER_DLL_EXPORT 16 | #define NAV_HELPER_DLL_LOCAL 17 | #endif 18 | #endif 19 | 20 | // Now we use the generic helper definitions above to define NAV_API and NAV_LOCAL. 21 | // NAV_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 22 | // NAV_LOCAL is used for non-api symbols. 23 | 24 | #ifdef NAV_DLL // defined if NAV is compiled as a DLL 25 | #ifdef NAV_DLL_EXPORTS // defined if we are building the NAV DLL (instead of using it) 26 | #define NAV_API NAV_HELPER_DLL_EXPORT 27 | #else 28 | #define NAV_API NAV_HELPER_DLL_IMPORT 29 | #endif // NAV_DLL_EXPORTS 30 | #define NAV_LOCAL NAV_HELPER_DLL_LOCAL 31 | #else // NAV_DLL is not defined: this means NAV is a static lib. 32 | #define NAV_API 33 | #define NAV_LOCAL 34 | #endif // NAV_DLL 35 | -------------------------------------------------------------------------------- /project_phd/phd/nav_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname nav_test) 3 | 4 | file (GLOB dir_27_headers *.h *.hpp) 5 | source_group("" FILES ${dir_27_headers}) 6 | set(all_headers ${dir_27_headers} ) 7 | 8 | file (GLOB dir_28_sources *.cpp *.c) 9 | source_group("" FILES ${dir_28_sources}) 10 | set(all_sources ${dir_28_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DATTITUDE_DLL) 21 | add_definitions(-DEARTH_DLL) 22 | add_definitions(-DFDYN_DLL) 23 | add_definitions(-DJAIL_DLL) 24 | # End Windows compatibility 25 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 26 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 27 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 28 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 29 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 30 | target_link_libraries(${prjname} debug jail${DEBUG_TARGET_SUFFIX} optimized jail) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/nav_test/Talign_coarse.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_TEST_ALIGN_COARSE 2 | #define NAV_TEST_ALIGN_COARSE 3 | 4 | #include "nav_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | #include "jail/unit_test.h" 8 | 9 | namespace nav { 10 | namespace test { 11 | 12 | class Talign_coarse: public ::jail::unit_test { 13 | public: 14 | /**< constructor based on counter */ 15 | explicit Talign_coarse(jail::counter&); 16 | /**< execute tests and write results on console */ 17 | void run() override; 18 | /**< specific tests */ 19 | 20 | void test_align_single(const ang::euler& euler_nb_truth, sens::logic::GYR_ID gyr_id, sens::logic::ACC_ID acc_id, sens::logic::MAG_ID mag_id); 21 | void test_align_multiple(sens::logic::GYR_ID gyr_id, sens::logic::ACC_ID acc_id, sens::logic::MAG_ID mag_id); 22 | 23 | }; 24 | 25 | } // closes namespace test 26 | } // closes namespace nav 27 | 28 | #endif 29 | 30 | -------------------------------------------------------------------------------- /project_phd/phd/nav_test/Tsimple.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_TEST_SIMPLE 2 | #define NAV_TEST_SIMPLE 3 | 4 | #include "nav_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | namespace nav { 8 | namespace test { 9 | 10 | class Tsimple: public ::jail::unit_test { 11 | public: 12 | /**< constructor based on counter */ 13 | explicit Tsimple(jail::counter&); 14 | /**< execute tests and write results on console */ 15 | void run() override; 16 | /**< specific tests */ 17 | 18 | void test_straight_motion(); 19 | void test_straight_motion2(); 20 | void test_rotation_motion(); 21 | 22 | }; 23 | 24 | } // closes namespace test 25 | } // closes namespace nav 26 | 27 | #endif 28 | 29 | -------------------------------------------------------------------------------- /project_phd/phd/nav_test/Ttrj_sizes.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_TEST_TRJ_SiZES 2 | #define NAV_TEST_TRJ_SIZES 3 | 4 | #include "nav_test.h" 5 | #include "jail/unit_test.h" 6 | 7 | namespace nav { 8 | namespace test { 9 | 10 | class Ttrj_sizes: public ::jail::unit_test { 11 | public: 12 | /**< constructor based on counter */ 13 | explicit Ttrj_sizes(jail::counter&); 14 | /**< execute tests and write results on console */ 15 | void run() override; 16 | /**< specific tests */ 17 | 18 | void test_sizes01(); 19 | void test_sizes02(); 20 | void test_sizes03(); 21 | void test_sizes04(); 22 | void test_sizes05(); 23 | void test_sizes06(); 24 | void test_sizes07(); 25 | void test_sizes08(); 26 | void test_sizes11(); 27 | void test_sizes12(); 28 | void test_sizes13(); 29 | void test_sizes14(); 30 | void test_sizes15(); 31 | void test_sizes16(); 32 | void test_sizes17(); 33 | void test_sizes18(); 34 | void test_sizes21(); 35 | void test_sizes22(); 36 | void test_sizes23(); 37 | 38 | 39 | }; 40 | 41 | } // closes namespace test 42 | } // closes namespace nav 43 | 44 | #endif 45 | 46 | -------------------------------------------------------------------------------- /project_phd/phd/nav_test/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Tsimple.h" 3 | #include "Ttrj_sizes.h" 4 | #include "Talign_coarse.h" 5 | #include 6 | 7 | int main(int argc, char **argv) { 8 | 9 | jail::counter Ocounter; 10 | 11 | {nav::test::Talign_coarse o(Ocounter); o.run(); } 12 | {nav::test::Tsimple o(Ocounter); o.run(); } 13 | {nav::test::Ttrj_sizes o(Ocounter); o.run(); } 14 | 15 | Ocounter.write_results(); 16 | 17 | return 0; 18 | } 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /project_phd/phd/nav_test/nav_test.h: -------------------------------------------------------------------------------- 1 | #ifndef NAV_TEST_H_INCLUDED 2 | #define NAV_TEST_H_INCLUDED 3 | 4 | // 4251: some class or template needs to have dll-interface to be used by clients 5 | // of this class. No problem when reffers to templates, clients can link succesfully 6 | // because the class instantiation (the code) is in client side (so no link at all). 7 | // Disabling 4251 can hide a problem when this class (which is dll exported): either 8 | // (1) expose in non-private sections or (2) use in inline functions implementations, 9 | // types witch are not dll exported 10 | // 4996: MSVC has gone into full security-paranoia mode. std::copy issues this warning 11 | // when it is used with raw pointers, because when used incorrectly, it can result in 12 | // buffer overflows. But if code is OK, no problem. Stupid Microsoft warning. 13 | #if defined(_MSC_VER) 14 | # pragma warning(disable:4251) 15 | # pragma warning(disable:4996) 16 | #endif 17 | 18 | // Now we use the generic helper definitions above to define NAV_TEST_API and NAV_TEST_LOCAL. 19 | // NAV_TEST_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 20 | // NAV_TEST_LOCAL is used for non-api symbols. 21 | 22 | #ifdef NAV_TEST_DLL // defined if NAV_TEST is compiled as a DLL 23 | #ifdef NAV_TEST_DLL_EXPORTS // defined if we are building the NAV_TEST DLL (instead of using it) 24 | #define NAV_TEST_API NAV_PERM_HELPER_DLL_EXPORT 25 | #else 26 | #define NAV_TEST_API NAV_PERM_HELPER_DLL_IMPORT 27 | #endif // NAV_TEST_DLL_EXPORTS 28 | #define NAV_TEST_LOCAL NAV_PERM_HELPER_DLL_LOCAL 29 | #else // NAV_TEST_DLL is not defined: this means NAV_TEST is a static lib. 30 | #define NAV_TEST_API 31 | #define NAV_TEST_LOCAL 32 | #endif // NAV_TEST_DLL 33 | 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname results_ana_test) 3 | 4 | file (GLOB dir_27_headers *.h *.hpp) 5 | source_group("" FILES ${dir_27_headers}) 6 | set(all_headers ${dir_27_headers} ) 7 | 8 | file (GLOB dir_28_sources *.cpp *.c) 9 | source_group("" FILES ${dir_28_sources}) 10 | set(all_sources ${dir_28_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DATTITUDE_DLL) 21 | add_definitions(-DEARTH_DLL) 22 | add_definitions(-DFDYN_DLL) 23 | add_definitions(-DJAIL_DLL) 24 | # End Windows compatibility 25 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 26 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 27 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 28 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 29 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 30 | target_link_libraries(${prjname} debug jail${DEBUG_TARGET_SUFFIX} optimized jail) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/Tplots_att_filter.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_ANA_TEST_PLOTS_ATT_FILTER 2 | #define RESULTS_ANA_TEST_PLOTS_ATT_FILTER 3 | 4 | #include "results_ana_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_att_filter { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_att_filter(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | /**< reads the body attitude estimation results from three sets of files, the baseline, and two employing 23 | * different attitude filter implementations. 24 | * It shows results on console and also generates the following files (for thesis, not Matlab): 25 | * - "versus_att_filter_euler_deg.txt" --> to plot euler mean and std variation with time 26 | * - "versus_att_filter_euler_table.tex" --> script to directly generate table in Latex */ 27 | void obtain_euler_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 28 | 29 | /**< reads the horizontal ground velocity estimation results from three sets of files, the baseline, and two employing 30 | * different attitude filter implementations. 31 | * It shows results on console and also generates the following files (for thesis, not Matlab): 32 | * - "versus_att_filter_vned_mps.txt" --> to plot ground speed final error 33 | * - "versus_att_filter_vned_table.tex" --> script to directly generate table in Latex */ 34 | void obtain_vn_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 35 | 36 | /**< reads those time instants where the aircraft is turning and fills up a tet file "versus_att_filter_turn_location.txt" */ 37 | void obtain_turn_location_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 38 | 39 | /**< reads the final horizontal position results from three sets of files, the baseline, nd two employing 40 | * different attitude filter implementations. 41 | * It shows results on console and also generates the following files (for thesis, not Matlab): 42 | * - "versus_att_filter_pos_hor_m_pc.txt" --> to plot horizontal error mean and std variation with time 43 | * - "versus_att_filter_pos_h.tex" --> script to directly generate table in Latex */ 44 | void obtain_xhor_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 45 | }; 46 | 47 | } // closes namespace test 48 | } // closes namespace nav 49 | 50 | #endif 51 | 52 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/Tplots_att_filter_alter.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_ANA_TEST_PLOTS_ATT_FILTER_ALTER 2 | #define RESULTS_ANA_TEST_PLOTS_ATT_FILTER_ALTER 3 | 4 | #include "results_ana_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_att_filter_alter { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_att_filter_alter(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | /**< reads the body attitude estimation results from three sets of files, the baseline, and two employing 23 | * different attitude filter implementations. 24 | * It shows results on console and also generates the following files (for thesis, not Matlab): 25 | * - "versus_att_filter_alter_euler_deg.txt" --> to plot euler mean and std variation with time 26 | * - "versus_att_filter_alter_euler_table.tex" --> script to directly generate table in Latex */ 27 | void obtain_euler_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 28 | 29 | /**< reads the horizontal ground velocity estimation results from three sets of files, the baseline, and two employing 30 | * different attitude filter implementations. 31 | * It shows results on console and also generates the following files (for thesis, not Matlab): 32 | * - "versus_att_filter_alter_vned_mps.txt" --> to plot ground speed final error 33 | * - "versus_att_filter_alter_vned_table.tex" --> script to directly generate table in Latex */ 34 | void obtain_vn_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 35 | 36 | /**< reads those time instants where the aircraft is turning and fills up a tet file "versus_att_filter_turn_location.txt" */ 37 | void obtain_turn_location_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 38 | 39 | /**< reads the final horizontal position results from three sets of files, the baseline, nd two employing 40 | * different attitude filter implementations. 41 | * It shows results on console and also generates the following files (for thesis, not Matlab): 42 | * - "versus_att_filter_alter_pos_hor_m_pc.txt" --> to plot horizontal error mean and std variation with time 43 | * - "versus_att_filter_alter_pos_h.tex" --> script to directly generate table in Latex */ 44 | void obtain_xhor_att_filter_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 45 | }; 46 | 47 | } // closes namespace test 48 | } // closes namespace nav 49 | 50 | #endif 51 | 52 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/Tplots_gnss.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_ANA_TEST_PLOTS_GNSS 2 | #define RESULTS_ANA_TEST_PLOTS_GNSS 3 | 4 | #include "results_ana_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_gnss { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_gnss(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests */ 20 | void run(); 21 | 22 | /**< reads the body attitude estimation results from two sets of files, the baseline and the one employing GNSS. 23 | * It shows results on console and also generates the following files (for thesis, not Matlab): 24 | * - "versus_gnss_att_euler_deg.txt" --> to plot euler mean and std variation with time 25 | * - "versus_gnss_att_euler_table.tex" --> script to directly generate table in Latex */ 26 | void obtain_euler_metrics(const std::string& st_first_folder, const std::string& st_first_folder_gnss, unsigned short& seed_init, unsigned short& seed_end); 27 | 28 | 29 | /**< reads the final altitude estimation results from two sets of files, the baseline and the one employing GNSS. 30 | * It shows results on console and also generates the following files (for thesis, not Matlab): 31 | * - "versus_gnss_pos_h_m.txt" --> to plot altitude mean and std variation with time 32 | * - "versus_gnss_pos_h.tex" --> script to directly generate table in Latex */ 33 | void obtain_h_metrics(const std::string& st_first_folder, const std::string& st_first_folder_gnss, unsigned short& seed_init, unsigned short& seed_end); 34 | 35 | 36 | /**< reads the final horizontal position results from two sets of files, the baseline and the one employing GNSS. 37 | * It shows results on console and also generates the following files (for thesis, not Matlab): 38 | * - "versus_gnss_pos_hor_m_pc.txt" --> to plot horizontal error mean and std variation with time 39 | * - "versus_gnss_pos_h.tex" --> script to directly generate table in Latex */ 40 | void obtain_xhor_metrics(const std::string& st_first_folder, const std::string& st_first_folder_gnss, unsigned short& seed_init, unsigned short& seed_end); 41 | 42 | }; 43 | 44 | } // closes namespace test 45 | } // closes namespace nav 46 | 47 | #endif 48 | 49 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/Tplots_pos_filter.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_ANA_TEST_PLOTS_POS_FILTER 2 | #define RESULTS_ANA_TEST_PLOTS_POS_FILTER 3 | 4 | #include "results_ana_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_pos_filter { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_pos_filter(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | /**< reads the final horizontal position results from three sets of files, the baseline and two alternatives. 23 | * It shows results on console and also generates the following files (for thesis, not Matlab): 24 | * - "versus_integr_pos_hor_m_pc_part1.txt" --> to plot horizontal error mean and std variation with time 25 | * - "versus_integr_pos_hor_m_pc_part2.txt" --> to plot horizontal error mean and std variation with time */ 26 | void obtain_xhor_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 27 | 28 | /**< reads the final vertical position results from two sets of files, the baseline and one alternatives. 29 | * It shows results on console and also generates the following files (for thesis, not Matlab): 30 | * - "versus_integr_pos_h_m_part1.txt" --> to plot vertical error mean and std variation with time 31 | * - "versus_integr_pos_h_m_part2.txt" --> to plot vertical error mean and std variation with time */ 32 | void obtain_h_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 33 | 34 | }; 35 | 36 | } // closes namespace test 37 | } // closes namespace nav 38 | 39 | #endif 40 | 41 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/Tplots_sensors_air.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_ANA_TEST_PLOTS_AIR_SENSORS 2 | #define RESULTS_ANA_TEST_PLOTS_AIR_SENSORS 3 | 4 | #include "results_ana_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_sensors_air { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_sensors_air(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | /**< reads the air data estimation results from three sets of files, the baseline, one employing 23 | * worse air data sensors (OSP & OAT), and another employing even worse sensors. 24 | * It shows results on console and also generates the following files (for thesis, not Matlab): 25 | * - "versus_air_T_Hp_DeltaT_table.tex" --> script to directly generate table in Latex */ 26 | void obtain_other_air_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 27 | 28 | /**< reads the body attitude estimation results from three sets of files, the baseline, one employing 29 | * worse air data sensors (OSP & OAT), and another employing even worse sensors. 30 | * It shows results on console and also generates the following files (for thesis, not Matlab): 31 | * - "versus_air_euler_table.tex" --> script to directly generate table in Latex */ 32 | void obtain_euler_air_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 33 | 34 | /**< reads the final altitude estimation results from three sets of files, the baseline, one employing 35 | * worse air data sensors (OSP & OAT), and another employing even worse sensors. 36 | * It shows results on console and also generates the following files (for thesis, not Matlab): 37 | * - "versus_air_h_m.txt" --> to plot altitude mean and std variation with time 38 | * - "versus_air_h.tex" --> script to directly generate table in Latex */ 39 | void obtain_h_air_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 40 | 41 | 42 | }; 43 | 44 | 45 | 46 | } // closes namespace test 47 | } // closes namespace nav 48 | 49 | #endif 50 | 51 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Tplots_gnss.h" 3 | #include "Tplots_pos_filter.h" 4 | #include "Tplots_att_filter.h" 5 | #include "Tplots_att_filter_alter.h" 6 | #include "Tplots_sensors_bias.h" 7 | #include "Tplots_sensors_gyr.h" 8 | #include "Tplots_sensors_acc.h" 9 | #include "Tplots_sensors_mag.h" 10 | #include "Tplots_sensors_air.h" 11 | #include "Tplots_sensors_vtasb.h" 12 | #include "Tplots_init.h" 13 | #include 14 | 15 | int main(int argc, char **argv) { 16 | 17 | unsigned short seed_init = 1; 18 | unsigned short seed_end = 100; 19 | 20 | {nav::test::Tplots_gnss o(seed_init, seed_end); o.run(); } 21 | {nav::test::Tplots_pos_filter o(seed_init, seed_end); o.run(); } 22 | {nav::test::Tplots_att_filter o(seed_init, seed_end); o.run(); } 23 | {nav::test::Tplots_att_filter_alter o(seed_init, seed_end); o.run(); } 24 | {nav::test::Tplots_sensors_bias o(seed_init, seed_end); o.run(); } 25 | {nav::test::Tplots_sensors_gyr o(seed_init, seed_end); o.run(); } 26 | {nav::test::Tplots_sensors_acc o(seed_init, seed_end); o.run(); } 27 | {nav::test::Tplots_sensors_mag o(seed_init, seed_end); o.run(); } 28 | {nav::test::Tplots_sensors_vtasb o(seed_init, seed_end); o.run(); } 29 | {nav::test::Tplots_sensors_air o(seed_init, seed_end); o.run(); } 30 | {nav::test::Tplots_init o(seed_init, seed_end); o.run(); } 31 | 32 | return 0; 33 | } 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /project_phd/phd/results_ana_test/results_ana_test.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_ANA_TEST_H_INCLUDED 2 | #define RESULTS_ANA_TEST_H_INCLUDED 3 | 4 | // 4251: some class or template needs to have dll-interface to be used by clients 5 | // of this class. No problem when reffers to templates, clients can link succesfully 6 | // because the class instantiation (the code) is in client side (so no link at all). 7 | // Disabling 4251 can hide a problem when this class (which is dll exported): either 8 | // (1) expose in non-private sections or (2) use in inline functions implementations, 9 | // types witch are not dll exported 10 | // 4996: MSVC has gone into full security-paranoia mode. std::copy issues this warning 11 | // when it is used with raw pointers, because when used incorrectly, it can result in 12 | // buffer overflows. But if code is OK, no problem. Stupid Microsoft warning. 13 | #if defined(_MSC_VER) 14 | # pragma warning(disable:4251) 15 | # pragma warning(disable:4996) 16 | #endif 17 | 18 | // Now we use the generic helper definitions above to define RESULTS_ANA_TEST_API and RESULTS_ANA_TEST_LOCAL. 19 | // RESULTS_ANA_TEST_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 20 | // RESULTS_ANA_TEST_LOCAL is used for non-api symbols. 21 | 22 | #ifdef RESULTS_ANA_TEST_DLL // defined if RESULTS_ANA_TEST is compiled as a DLL 23 | #ifdef RESULTS_ANA_TEST_DLL_EXPORTS // defined if we are building the RESULTS_ANA_TEST DLL (instead of using it) 24 | #define RESULTS_ANA_TEST_API RESULTS_ANA_PERM_HELPER_DLL_EXPORT 25 | #else 26 | #define RESULTS_ANA_TEST_API RESULTS_ANA_PERM_HELPER_DLL_IMPORT 27 | #endif // RESULTS_ANA_TEST_DLL_EXPORTS 28 | #define RESULTS_ANA_TEST_LOCAL RESULTS_ANA_PERM_HELPER_DLL_LOCAL 29 | #else // RESULTS_ANA_TEST_DLL is not defined: this means RESULTS_ANA_TEST is a static lib. 30 | #define RESULTS_ANA_TEST_API 31 | #define RESULTS_ANA_TEST_LOCAL 32 | #endif // RESULTS_ANA_TEST_DLL 33 | 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | set(prjname results_sim_test) 3 | 4 | file (GLOB dir_27_headers *.h *.hpp) 5 | source_group("" FILES ${dir_27_headers}) 6 | set(all_headers ${dir_27_headers} ) 7 | 8 | file (GLOB dir_28_sources *.cpp *.c) 9 | source_group("" FILES ${dir_28_sources}) 10 | set(all_sources ${dir_28_sources} ) 11 | 12 | add_executable(${prjname} ${all_headers} ${all_sources}) 13 | 14 | set_target_properties(${prjname} PROPERTIES DEBUG_OUTPUT_NAME ${prjname}${DEBUG_TARGET_SUFFIX}) 15 | set_target_properties(${prjname} PROPERTIES RELEASE_OUTPUT_NAME ${prjname}) 16 | 17 | include_directories(${PROJECTS_SRC_ROOT}/phd) 18 | 19 | # Following lines are for Windows compatibility 20 | add_definitions(-DATTITUDE_DLL) 21 | add_definitions(-DEARTH_DLL) 22 | add_definitions(-DFDYN_DLL) 23 | add_definitions(-DJAIL_DLL) 24 | # End Windows compatibility 25 | target_link_libraries(${prjname} debug math${DEBUG_TARGET_SUFFIX} optimized math) 26 | target_link_libraries(${prjname} debug ang${DEBUG_TARGET_SUFFIX} optimized ang) 27 | target_link_libraries(${prjname} debug env${DEBUG_TARGET_SUFFIX} optimized env) 28 | target_link_libraries(${prjname} debug acft${DEBUG_TARGET_SUFFIX} optimized acft) 29 | target_link_libraries(${prjname} debug nav${DEBUG_TARGET_SUFFIX} optimized nav) 30 | target_link_libraries(${prjname} debug jail${DEBUG_TARGET_SUFFIX} optimized jail) 31 | target_link_libraries(${prjname} ${Boost_LIBRARIES}) 32 | 33 | foreach(A_LIB ${EIGEN_LIBS_RELEASE}) 34 | target_link_libraries(${prjname} optimized ${A_LIB}) 35 | endforeach() 36 | foreach(A_LIB ${EIGEN_LIBS_DEBUG}) 37 | target_link_libraries(${prjname} debug ${A_LIB}) 38 | endforeach() 39 | 40 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/Tplots_air.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_SIM_TEST_PLOTS_AIR 2 | #define RESULTS_SIM_TEST_PLOTS_AIR 3 | 4 | #include "results_sim_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_air { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_air(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | /**< reads the airspeed vector air data filter results from a group of files (those between the initial 23 | * and final seeds) for the trajectories identified by the initial string (which includes a seed but may 24 | * not be read at all if it does not fall in between the input seeds). It shows results on console and 25 | * also generates the following files (for thesis, not Matlab): 26 | * - "error_filter_air_vtasb_mpsdeg.txt" --> to plot vtas, alpha, and beta mean and std variation with time (only if flag_bias is false) 27 | * - "error_filter_air_vtasb_mpsdeg_lsqfit.txt" --> to plot least squares on previous plot (only if flag_bias is false) 28 | * - "error_filter_air_vtasb_table.tex" --> script to directly generate table in Latex (only if flag_bias is false) 29 | * - "error_filter_air_vtasb_bias_table.tex" --> script to directly generate table in Latex including biases (only if flag_bias is true) 30 | * - "error_filter_air_vtasb_lsqfit_table.tex --> script to directly generate lsq table in Latex (only if flag_bias is false) */ 31 | void obtain_vtasb_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end, bool flag_bias); 32 | 33 | /**< reads the other air data filter results from a group of files (those between the initial 34 | * and final seeds) for the trajectories identified by the initial string (which includes a seed but may 35 | * not be read at all if it does not fall in between the input seeds). It shows results on console and 36 | * also generates the following files (for thesis, not Matlab): 37 | * - "error_filter_air_other_mdeg.txt" --> to plot T, Hp, DeltaT mean and std variation with time 38 | * - "error_filter_air_other_mdeg_lsqfit.txt" --> to plot least squares on previous plot 39 | * - "error_filter_air_other_table.tex" --> script to directly generate table in Latex 40 | * - "error_filter_air_other_lsqfit_table.tex --> script to directly generate lsq table in Latex */ 41 | void obtain_other_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 42 | 43 | /**< reads the airspeed estimation results from a single file and generates the file 44 | * "error_filter_air_single_vtas_mps.txt" (to be added to thesis, not Matlab) */ 45 | void obtain_vtas_single(const std::string& st_folder); 46 | /**< reads the pressure altitude estimation results from a single file and generates the file 47 | * "error_filter_air_single_Hp_m.txt" (to be added to thesis, not Matlab) */ 48 | void obtain_Hp_single(const std::string& st_folder); 49 | /**< reads the temperature offset results from a single file and generates the file 50 | * "error_filter_air_single_DeltaT_degK.txt" (to be added to thesis, not Matlab) */ 51 | void obtain_DeltaT_single(const std::string& st_folder); 52 | }; 53 | 54 | } // closes namespace test 55 | } // closes namespace nav 56 | 57 | #endif 58 | 59 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/Tplots_control.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_SIM_TEST_PLOTS_CONTROL 2 | #define RESULTS_SIM_TEST_PLOTS_CONTROL 3 | 4 | #include "results_sim_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_control { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_control(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | /**< reads the pressure altitude and true airspeed control results from a group of files (those between the 23 | * initial and final seeds) for the trajectories identified by the initial string (which includes a seed 24 | * but may not be read at all if it does not fall in between the input seeds). It shows results on console 25 | * and also generates the following files (for thesis, not Matlab): 26 | * - error_control_Hp_m.txt --> to plot Hp mean and std variation with time 27 | * - error_control_Hp_m_lsqfit.txt --> to plot least squares on previous plot 28 | * - error_control_vtas_m.txt --> to plot vtas mean and std variation with time 29 | * - error_control_vtas_mps_lsqfit.txt --> to plot least squares on previous plot 30 | * - error_control_Hp_vtas_table.tex --> script to directly generate table in Latex 31 | * - error_control_Hp_vtas_lsqfit_table.tex --> script to directly generate lsq table in Latex */ 32 | void obtain_Hp_vtas_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 33 | 34 | 35 | /**< reads the absolute bearing and sideslip control results from a group of files (those between the 36 | * initial and final seeds) for the trajectories identified by the initial string (which includes a seed 37 | * but may not be read at all if it does not fall in between the input seeds). It shows results on console 38 | * and also generates the following files (for thesis, not MatLab): 39 | * - error_control_chi_deg.txt --> to plot chi mean and std variation with time 40 | * - error_control_chi_deg_lsqfit.txt --> to plot least squares on previous plot 41 | * - error_control_beta_deg.txt --> to pot beta mean and std variation with time 42 | * - error_control_beta_deg_lsqfit.txt --> to plot least squares on previous plot 43 | * - error_control_chi_beta_table.tex --> script to directly generate table in Latex 44 | * - error_control_chi_beta_lsqfit_table.tex --> script to directly generate lsq table in Latex */ 45 | void obtain_chi_beta_metrics(const std::string& st_first_folder, unsigned short& seed_init, unsigned short& seed_end); 46 | 47 | }; 48 | 49 | 50 | 51 | } // closes namespace test 52 | } // closes namespace nav 53 | 54 | #endif 55 | 56 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/Tplots_number.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_SIM_TEST_PLOTS_NUMBER 2 | #define RESULTS_SIM_TEST_PLOTS_NUMBER 3 | 4 | #include "results_sim_test.h" 5 | #include 6 | 7 | namespace nav { 8 | namespace test { 9 | 10 | class Tplots_number { 11 | private: 12 | unsigned short _seed_init; 13 | unsigned short _seed_end; 14 | public: 15 | /**< constructor based on counter */ 16 | explicit Tplots_number(unsigned short& seed_init, unsigned short& seed_end); 17 | 18 | /**< execute tests and write results on console */ 19 | void run(); 20 | 21 | /**< checks the aggregated means taking into account progressively from seed_init to seed_end executions, 22 | * and computes aggregated mean and std for atttiude, error, final geometric altitude error, and final 23 | * ground velocity error. Generates the following files: 24 | * - "error_filter_number_euler_deg.txt" --> to plot attitude aggregated metrics with nEX 25 | * - "error_filter_number_hend_m.txt" --> to plot final altitude aggregated metrics with nEX 26 | * - "error_filter_number_vnend_mps.txt" --> to plot final ground velocity aggregated metrics with nEX */ 27 | void obtain_optimum_number(const std::string& st_first_folder, const unsigned short& seed_init, const unsigned short& seed_end); 28 | 29 | }; 30 | 31 | 32 | 33 | } // closes namespace test 34 | } // closes namespace nav 35 | 36 | #endif 37 | 38 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/Tplots_seeds.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_SIM_TEST_PLOTS_SEEDS 2 | #define RESULTS_SIM_TEST_PLOTS_SEEDS 3 | 4 | #include "results_sim_test.h" 5 | #include "ang/rotate/euler.h" 6 | #include "acft/sens/logic.h" 7 | 8 | namespace nav { 9 | namespace test { 10 | 11 | class Tplots_seeds { 12 | private: 13 | unsigned short _seed_init; 14 | unsigned short _seed_end; 15 | public: 16 | /**< constructor based on counter */ 17 | explicit Tplots_seeds(unsigned short& seed_init, unsigned short& seed_end); 18 | 19 | /**< execute tests and write results on console */ 20 | void run(); 21 | 22 | void test_guidance_bearing (unsigned short& seed_init, unsigned short& seed_end); 23 | void test_guidance_alt_speed(unsigned short& seed_init, unsigned short& seed_end); 24 | void test_offsets (unsigned short& seed_init, unsigned short& seed_end); 25 | void test_wind (unsigned short& seed_init, unsigned short& seed_end); 26 | void test_gravity (unsigned short& seed_init, unsigned short& seed_end); 27 | void test_magnetic (unsigned short& seed_init, unsigned short& seed_end); 28 | 29 | }; 30 | 31 | } // closes namespace test 32 | } // closes namespace nav 33 | 34 | #endif 35 | 36 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "Tplots_seeds.h" 3 | #include "Tplots_control.h" 4 | #include "Tplots_air.h" 5 | #include "Tplots_attitude.h" 6 | #include "Tplots_pos.h" 7 | #include "Tplots_number.h" 8 | #include 9 | 10 | int main(int argc, char **argv) { 11 | 12 | unsigned short seed_init = 1; 13 | unsigned short seed_end = 100; 14 | 15 | {nav::test::Tplots_seeds o(seed_init, seed_end); o.run(); } 16 | {nav::test::Tplots_control o(seed_init, seed_end); o.run(); } 17 | {nav::test::Tplots_air o(seed_init, seed_end); o.run(); } 18 | {nav::test::Tplots_attitude o(seed_init, seed_end); o.run(); } 19 | {nav::test::Tplots_pos o(seed_init, seed_end); o.run(); } 20 | {nav::test::Tplots_number o(seed_init, seed_end); o.run(); } 21 | 22 | return 0; 23 | } 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /project_phd/phd/results_sim_test/results_sim_test.h: -------------------------------------------------------------------------------- 1 | #ifndef RESULTS_SIM_TEST_H_INCLUDED 2 | #define RESULTS_SIM_TEST_H_INCLUDED 3 | 4 | // 4251: some class or template needs to have dll-interface to be used by clients 5 | // of this class. No problem when reffers to templates, clients can link succesfully 6 | // because the class instantiation (the code) is in client side (so no link at all). 7 | // Disabling 4251 can hide a problem when this class (which is dll exported): either 8 | // (1) expose in non-private sections or (2) use in inline functions implementations, 9 | // types witch are not dll exported 10 | // 4996: MSVC has gone into full security-paranoia mode. std::copy issues this warning 11 | // when it is used with raw pointers, because when used incorrectly, it can result in 12 | // buffer overflows. But if code is OK, no problem. Stupid Microsoft warning. 13 | #if defined(_MSC_VER) 14 | # pragma warning(disable:4251) 15 | # pragma warning(disable:4996) 16 | #endif 17 | 18 | // Now we use the generic helper definitions above to define RESULTS_SIM_TEST_API and RESULTS_SIM_TEST_LOCAL. 19 | // RESULTS_SIM_TEST_API is used for the public API symbols. It either DLL imports or DLL exports (or does nothing for static build) 20 | // RESULTS_SIM_TEST_LOCAL is used for non-api symbols. 21 | 22 | #ifdef RESULTS_SIM_TEST_DLL // defined if RESULTS_SIM_TEST is compiled as a DLL 23 | #ifdef RESULTS_SIM_TEST_DLL_EXPORTS // defined if we are building the RESULTS_SIM_TEST DLL (instead of using it) 24 | #define RESULTS_SIM_TEST_API RESULTS_SIM_PERM_HELPER_DLL_EXPORT 25 | #else 26 | #define RESULTS_SIM_TEST_API RESULTS_SIM_PERM_HELPER_DLL_IMPORT 27 | #endif // RESULTS_SIM_TEST_DLL_EXPORTS 28 | #define RESULTS_SIM_TEST_LOCAL RESULTS_SIM_PERM_HELPER_DLL_LOCAL 29 | #else // RESULTS_SIM_TEST_DLL is not defined: this means RESULTS_SIM_TEST is a static lib. 30 | #define RESULTS_SIM_TEST_API 31 | #define RESULTS_SIM_TEST_LOCAL 32 | #endif // RESULTS_SIM_TEST_DLL 33 | 34 | 35 | #endif 36 | --------------------------------------------------------------------------------