Skip to content

Commit

Permalink
also ensure we use same gravity magnitude
Browse files Browse the repository at this point in the history
  • Loading branch information
goldbattle committed Aug 16, 2023
1 parent e039ecb commit a915584
Show file tree
Hide file tree
Showing 5 changed files with 27 additions and 18 deletions.
18 changes: 11 additions & 7 deletions scripts/commands_eurocmav.yaml
Original file line number Diff line number Diff line change
@@ -1,22 +1,26 @@

vi_map_folder_paths:
- /datasets/euroc_mav/maplab/V1_01_easy
- /datasets/euroc_mav/maplab/V1_02_medium
- /datasets/euroc_mav/maplab/V1_03_difficult
- /datasets/euroc_mav/maplab/V2_01_easy
- /datasets/euroc_mav/maplab/V2_02_medium
- /datasets/euroc_mav/maplab/V2_03_difficult
- /datasets/euroc_mav/maplab/raw_maps/V1_01_easy
- /datasets/euroc_mav/maplab/raw_maps/V1_02_medium
- /datasets/euroc_mav/maplab/raw_maps/V1_03_difficult
- /datasets/euroc_mav/maplab/raw_maps/V2_01_easy
- /datasets/euroc_mav/maplab/raw_maps/V2_02_medium
- /datasets/euroc_mav/maplab/raw_maps/V2_03_difficult
commands:
- load --map_folder=<CURRENT_VIMAP_FOLDER>
- retriangulate_landmarks
- v --vis_color_by_mission
- optvi --ba_num_iterations=5 -ba_visualize_every_n_iterations=1
- remove_invalid_observations
- evaluate_landmark_quality
- remove_bad_landmarks
- retriangulate_landmarks
- loopclosure_all_missions
- optvi --ba_num_iterations=5 -ba_visualize_every_n_iterations=1
- retriangulate_landmarks
- loopclosure_all_missions
- optvi --ba_num_iterations=30 -ba_visualize_every_n_iterations=5
- optvi --ba_num_iterations=30 -ba_visualize_every_n_iterations=1
- remove_invalid_observations
- evaluate_landmark_quality
- remove_bad_landmarks
- save --map_folder=<CURRENT_VIMAP_FOLDER>_result
Expand Down
22 changes: 13 additions & 9 deletions scripts/commands_rpngplane.yaml
Original file line number Diff line number Diff line change
@@ -1,24 +1,28 @@

vi_map_folder_paths:
- /datasets/rpng_plane/maplab/table_01
- /datasets/rpng_plane/maplab/table_02
- /datasets/rpng_plane/maplab/table_03
- /datasets/rpng_plane/maplab/table_04
- /datasets/rpng_plane/maplab/table_05
- /datasets/rpng_plane/maplab/table_06
- /datasets/rpng_plane/maplab/table_07
- /datasets/rpng_plane/maplab/table_08
- /datasets/rpng_plane/maplab/raw_maps/table_01
- /datasets/rpng_plane/maplab/raw_maps/table_02
- /datasets/rpng_plane/maplab/raw_maps/table_03
- /datasets/rpng_plane/maplab/raw_maps/table_04
- /datasets/rpng_plane/maplab/raw_maps/table_05
- /datasets/rpng_plane/maplab/raw_maps/table_06
- /datasets/rpng_plane/maplab/raw_maps/table_07
- /datasets/rpng_plane/maplab/raw_maps/table_08
commands:
- load --map_folder=<CURRENT_VIMAP_FOLDER>
- retriangulate_landmarks
- v --vis_color_by_mission
- optvi --ba_num_iterations=5 -ba_visualize_every_n_iterations=1
- remove_invalid_observations
- evaluate_landmark_quality
- remove_bad_landmarks
- retriangulate_landmarks
- loopclosure_all_missions
- optvi --ba_num_iterations=5 -ba_visualize_every_n_iterations=1
- retriangulate_landmarks
- loopclosure_all_missions
- optvi --ba_num_iterations=30 -ba_visualize_every_n_iterations=5
- optvi --ba_num_iterations=30 -ba_visualize_every_n_iterations=1
- remove_invalid_observations
- evaluate_landmark_quality
- remove_bad_landmarks
- save --map_folder=<CURRENT_VIMAP_FOLDER>_result
Expand Down
2 changes: 1 addition & 1 deletion scripts/process_eurocmav.sh
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ roslaunch ov_maplab serial.launch \
use_stereo:="true" \
config:="euroc_mav" \
dataset:="${bagnames[i]}" \
mapfolder:="/datasets/euroc_mav/maplab/raw_maps/${bagnames[i]}/" \
dolivetraj:="true" &> /dev/null

# print out the time elapsed
Expand All @@ -58,7 +59,6 @@ echo "BASH: full maplab opt took $elapsed seconds";

# fix our permissions...
sudo chmod -R 777 /datasets/euroc_mav/maplab/
sudo chown -R patrick /datasets/euroc_mav/maplab/

# print out the time elapsed
big_end_time="$(date -u +%s)"
Expand Down
2 changes: 1 addition & 1 deletion scripts/process_rpngplane.sh
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ roslaunch ov_maplab serial.launch \
use_stereo:="true" \
config:="rpng_plane" \
dataset:="${bagnames[i]}" \
mapfolder:="/datasets/rpng_plane/maplab/raw_maps/${bagnames[i]}/" \
dolivetraj:="true" &> /dev/null

# print out the time elapsed
Expand All @@ -60,7 +61,6 @@ echo "BASH: full maplab opt took $elapsed seconds";

# fix our permissions...
sudo chmod -R 777 /datasets/rpng_plane/maplab/
sudo chown -R patrick /datasets/rpng_plane/maplab/

# print out the time elapsed
big_end_time="$(date -u +%s)"
Expand Down
1 change: 1 addition & 0 deletions src/mapper/MapBuilder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,7 @@ MapBuilder::MapBuilder(std::shared_ptr<ros::NodeHandle> nh, std::shared_ptr<VioM
aslam::SensorId imu_sensor_id = aslam::createRandomId<aslam::SensorId>();
vi_map::Imu::UniquePtr imu_sensor = aligned_unique<vi_map::Imu>(imu_sensor_id, static_cast<std::string>(kImuHardwareId));
imu_sensor->setImuSigmas(imu_sigmas);
imu_sensor->setGravityMagnitude(_params.gravity_mag);

// Create our camera object
std::string cam_label = "ncameras";
Expand Down

0 comments on commit a915584

Please sign in to comment.