diff --git a/ReadMe.md b/ReadMe.md index 13caf9ee7..1448a49c1 100644 --- a/ReadMe.md +++ b/ReadMe.md @@ -21,7 +21,7 @@ details on what the system supports. ## News / Events - +* **May 11, 2023** - Inertial intrinsic support released as part of v2.7 along with a few bug fixes and improvements to stereo KLT tracking. Please check out the [release page](https://github.com/rpng/open_vins/releases/tag/v2.7) for details. * **April 15, 2023** - Minor update to v2.6.3 to support incremental feature triangulation of active features for downstream applications, faster zero-velocity update, small bug fixes, some example realsense configurations, and cached fast state prediction. Please check out the [release page](https://github.com/rpng/open_vins/releases/tag/v2.6.3) for details. * **April 3, 2023** - We have released a monocular plane-aided VINS, termed [ov_plane](https://github.com/rpng/ov_plane), which leverages the OpenVINS project. Both now support the released [Indoor AR Table](https://github.com/rpng/ar_table_dataset) dataset. * **July 14, 2022** - Improved feature extraction logic for >100hz tracking, some bug fixes and updated scripts. See v2.6.1 [PR#259](https://github.com/rpng/open_vins/pull/259) and v2.6.2 [PR#264](https://github.com/rpng/open_vins/pull/264). diff --git a/config/rpng_plane/estimator_config.yaml b/config/rpng_plane/estimator_config.yaml index b1ee58b27..04c0774e4 100644 --- a/config/rpng_plane/estimator_config.yaml +++ b/config/rpng_plane/estimator_config.yaml @@ -3,9 +3,7 @@ verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT use_fej: true # if first-estimate Jacobians should be used (enable for good consistency) -use_imuavg: true # if using discrete integration, if we should average sequential IMU measurements to "smooth" it -use_rk4int: true # if rk4 integration should be used (overrides imu averaging) - +integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used) use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints between pairs max_cameras: 1 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking) diff --git a/config/rs_d455/estimator_config.yaml b/config/rs_d455/estimator_config.yaml index 64d705ffd..a1e78fc2f 100644 --- a/config/rs_d455/estimator_config.yaml +++ b/config/rs_d455/estimator_config.yaml @@ -3,9 +3,7 @@ verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT use_fej: true # if first-estimate Jacobians should be used (enable for good consistency) -use_imuavg: true # if using discrete integration, if we should average sequential IMU measurements to "smooth" it -use_rk4int: true # if rk4 integration should be used (overrides imu averaging) - +integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used) use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints between pairs max_cameras: 1 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking) diff --git a/config/rs_t265/estimator_config.yaml b/config/rs_t265/estimator_config.yaml index 6cfad3214..4604ede56 100644 --- a/config/rs_t265/estimator_config.yaml +++ b/config/rs_t265/estimator_config.yaml @@ -3,9 +3,7 @@ verbosity: "INFO" # ALL, DEBUG, INFO, WARNING, ERROR, SILENT use_fej: true # if first-estimate Jacobians should be used (enable for good consistency) -use_imuavg: true # if using discrete integration, if we should average sequential IMU measurements to "smooth" it -use_rk4int: true # if rk4 integration should be used (overrides imu averaging) - +integration: "rk4" # discrete, rk4, analytical (if rk4 or analytical used then analytical covariance propagation is used) use_stereo: true # if we have more than 1 camera, if we should try to track stereo constraints between pairs max_cameras: 2 # how many cameras we have 1 = mono, 2 = stereo, >2 = binocular (all mono tracking) diff --git a/ov_core/src/utils/opencv_yaml_parse.h b/ov_core/src/utils/opencv_yaml_parse.h index 568f7011b..3ee981483 100644 --- a/ov_core/src/utils/opencv_yaml_parse.h +++ b/ov_core/src/utils/opencv_yaml_parse.h @@ -43,7 +43,8 @@ namespace ov_core { * @brief Helper class to do OpenCV yaml parsing from both file and ROS. * * The logic is as follows: - * - Given a path to the main config file we will load it into our [cv::FileStorage](https://docs.opencv.org/4.x/da/d56/classcv_1_1FileStorage.html) object. + * - Given a path to the main config file we will load it into our + * [cv::FileStorage](https://docs.opencv.org/4.x/da/d56/classcv_1_1FileStorage.html) object. * - From there the user can request for different parameters of different types from the config. * - If we have ROS, then we will also check to see if the user has overridden any config files via ROS. * - The ROS parameters always take priority over the ones in our config. diff --git a/ov_core/src/utils/sensor_data.h b/ov_core/src/utils/sensor_data.h index 17d01f345..98811f638 100644 --- a/ov_core/src/utils/sensor_data.h +++ b/ov_core/src/utils/sensor_data.h @@ -26,8 +26,6 @@ #include #include -#include "utils/quat_ops.h" - namespace ov_core { /** diff --git a/ov_msckf/launch/serial.launch b/ov_msckf/launch/serial.launch index 7ce9ed8f9..0ba496e34 100644 --- a/ov_msckf/launch/serial.launch +++ b/ov_msckf/launch/serial.launch @@ -11,7 +11,7 @@ - + diff --git a/ov_msckf/scripts/run_ros_eth.sh b/ov_msckf/scripts/run_ros_eth.sh index 91cd27878..9aa43dc31 100755 --- a/ov_msckf/scripts/run_ros_eth.sh +++ b/ov_msckf/scripts/run_ros_eth.sh @@ -23,11 +23,11 @@ bagnames=( "V2_01_easy" "V2_02_medium" "V2_03_difficult" - "MH_01_easy" - "MH_02_easy" - "MH_03_medium" - "MH_04_difficult" - "MH_05_difficult" +# "MH_01_easy" +# "MH_02_easy" +# "MH_03_medium" +# "MH_04_difficult" +# "MH_05_difficult" ) # how far we should start into the dataset @@ -49,8 +49,8 @@ bagstarttimes=( # location to save log files into save_path1="/home/patrick/github/pubs_data/pgeneva/2023_openvins_reproduce/exp_euroc/algorithms" save_path2="/home/patrick/github/pubs_data/pgeneva/2023_openvins_reproduce/exp_euroc/timings" -bag_path="/home/patrick/datasets/euroc_mav/" -ov_ver="2.6.3" +bag_path="/media/patrick/Windows/datasets/euroc_mav/" +ov_ver="2.7" #============================================================= diff --git a/ov_msckf/scripts/run_ros_kaist.sh b/ov_msckf/scripts/run_ros_kaist.sh index bb92f00a5..bccace9a1 100755 --- a/ov_msckf/scripts/run_ros_kaist.sh +++ b/ov_msckf/scripts/run_ros_kaist.sh @@ -18,7 +18,7 @@ modes=( # dataset locations bagnames=( "urban28" - "urban32" +# "urban32" # "urban34" # too strong of sun... "urban38" "urban39" @@ -37,8 +37,8 @@ bagstarttimes=( # location to save log files into save_path1="/home/patrick/github/pubs_data/pgeneva/2023_openvins_reproduce/exp_kaist/algorithms" save_path2="/home/patrick/github/pubs_data/pgeneva/2023_openvins_reproduce/exp_kaist/timings" -bag_path="/home/patrick/datasets/euroc_mav/" -ov_ver="2.6.3" +bag_path="/media/patrick/Windows/datasets/kaist/" +ov_ver="2.7" #============================================================= diff --git a/ov_msckf/scripts/run_ros_tumvi.sh b/ov_msckf/scripts/run_ros_tumvi.sh index 76e15bf5f..15aace19f 100755 --- a/ov_msckf/scripts/run_ros_tumvi.sh +++ b/ov_msckf/scripts/run_ros_tumvi.sh @@ -39,8 +39,8 @@ bagstarttimes=( # location to save log files into save_path1="/home/patrick/github/pubs_data/pgeneva/2023_openvins_reproduce/exp_tumvi/algorithms" save_path2="/home/patrick/github/pubs_data/pgeneva/2023_openvins_reproduce/exp_tumvi/timings" -bag_path="/home/patrick/datasets/tum_vi/" -ov_ver="2.6.3" +bag_path="/media/patrick/Windows/datasets/tum_vi/" +ov_ver="2.7" #============================================================= diff --git a/ov_msckf/scripts/run_sim_calib.sh b/ov_msckf/scripts/run_sim_calib.sh index 40a7d72ce..c1837ea66 100755 --- a/ov_msckf/scripts/run_sim_calib.sh +++ b/ov_msckf/scripts/run_sim_calib.sh @@ -10,10 +10,10 @@ source ${SCRIPT_DIR}/../../../../devel/setup.bash # datasets datasets=( - "udel_gore" +# "udel_gore" # "udel_arl" # "udel_gore_zupt" -# "tum_corridor1_512_16_okvis" + "tum_corridor1_512_16_okvis" ) # If we want to calibrate parameters diff --git a/ov_msckf/scripts/run_sim_cams.sh b/ov_msckf/scripts/run_sim_cams.sh index 132d02dc4..12f18e753 100755 --- a/ov_msckf/scripts/run_sim_cams.sh +++ b/ov_msckf/scripts/run_sim_cams.sh @@ -10,10 +10,10 @@ source ${SCRIPT_DIR}/../../../../devel/setup.bash # datasets datasets=( - "udel_gore" +# "udel_gore" # "udel_arl" # "udel_gore_zupt" -# "tum_corridor1_512_16_okvis" + "tum_corridor1_512_16_okvis" ) # what modes to use diff --git a/ov_msckf/scripts/run_sim_featrep.sh b/ov_msckf/scripts/run_sim_featrep.sh index b97c81533..3edaa5c0d 100755 --- a/ov_msckf/scripts/run_sim_featrep.sh +++ b/ov_msckf/scripts/run_sim_featrep.sh @@ -10,10 +10,10 @@ source ${SCRIPT_DIR}/../../../../devel/setup.bash # datasets datasets=( - "udel_gore" +# "udel_gore" # "udel_arl" # "udel_gore_zupt" -# "tum_corridor1_512_16_okvis" + "tum_corridor1_512_16_okvis" ) # estimator configurations