Skip to content

Commit

Permalink
use the urban28 config info
Browse files Browse the repository at this point in the history
  • Loading branch information
goldbattle committed Jan 5, 2023
1 parent c325943 commit d171a03
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 22 deletions.
13 changes: 7 additions & 6 deletions config/kaist/kalibr_imucam_chain.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

cam0:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [-0.00413,-0.01966,0.99980,1.73944]
- [-0.99993,-0.01095,-0.00435,0.27803]
- [0.01103,-0.99975,-0.01962,-0.08785]
- [-0.00681,-0.01532,0.99987,1.71239]
- [-0.99998,0.00033,-0.00680,0.24740]
- [-0.00023,-0.99988,-0.01532,-0.11589]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [1]
camera_model: pinhole
Expand All @@ -16,9 +16,9 @@ cam0:

cam1:
T_imu_cam: #rotation from camera to IMU R_CtoI, position of camera in IMU p_CinI
- [-0.00768,-0.01509,0.99986,1.73376]
- [-0.99988,-0.01305,-0.00788,-0.19706]
- [0.01317,-0.99980,-0.01499,-0.08271]
- [-0.01036,-0.01075,0.99990,1.70544]
- [-0.99994,-0.00178,-0.01038,-0.22770]
- [0.00189,-0.99994,-0.01073,-0.11611]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
Expand All @@ -27,3 +27,4 @@ cam1:
intrinsics: [8.1378205539589999e+02,8.0852165574269998e+02,6.1386419539320002e+02,2.4941049348650000e+02]
resolution: [1280, 560]
rostopic: /stereo/right/image_raw

3 changes: 2 additions & 1 deletion docs/gs-datasets.dox
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,7 @@ The [KAIST urban dataset](https://sites.google.com/view/complex-urban-dataset) @
The dataset was collected in Korea with a vehicle equipped with stereo camera pair, 2d SICK LiDARs, 3d Velodyne LiDAR, Xsens IMU, fiber optic gyro (FoG), wheel encoders, and RKT GPS.
The camera is 10 Hz, while the Xsens IMU is 100 Hz sensing rate.
A groundtruth "baseline" trajectory is also provided which is the resulting output from fusion of the FoG, RKT GPS, and wheel encoders.
We provide [processing scripts](https://github.com/rpng/open_vins/tree/master/ov_data/kaist/matlab) to generate the calibration and groundtruth from the dataset's formats.

@m_class{m-block m-warning}

Expand Down Expand Up @@ -215,7 +216,7 @@ Typically we process the datasets at 1.5x rate so we get a ~20 Hz image feed and
The [KAIST VIO dataset](https://github.com/url-kaist/kaistviodataset) @cite Jeon2021RAL is a dataset of a MAV in an indoor 3.15 x 3.60 x 2.50 meter environment which undergoes various trajectory motions.
The camera is intel realsense D435i 25 Hz, while the IMU is 100 Hz sensing rate from the pixelhawk 4 unit.
A groundtruth "baseline" trajectory is also provided from a OptiTrack Mocap system at 50 Hz, the bag files have the marker body frame to IMU frame already applied.
This topic has been provided in ov_data for convinces sake.
This topic has been provided in ov_data for convenience sake.

@m_div{m-text-center}
| Dataset Name | Length (km) | Dataset Link | Groundtruth Traj. | Example Launch |
Expand Down
28 changes: 15 additions & 13 deletions ov_data/kaist/matlab/kaist_calculate_imu2cam.m
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,12 @@
close all;


% stereoParams.mat
% load their stereo parameters
% looks like they used the matlab calibration tool to get it.
% https://www.mathworks.com/help/vision/ref/stereoparameters.html#d117e94134
load ../raw/stereoParams.mat
%stereoParams = toStruct(stereoParams);
stereoParams = toStruct(stereoParams);

% transform between the left (stereo pair base) and the right camera
% the units of the stereo parameters are millimeters
Expand All @@ -19,21 +20,23 @@
0 0 0 1
];


% T_LtoR = zeros(4,4);
% T_LtoR(1,1) = 1;
% T_LtoR(1,4) = -0.4751;
% T_LtoR(2,2) = 1;
% T_LtoR(3,3) = 1;
% T_LtoR(4,4) = 1;
% Use this computed output if you do not have the toolbox
% TODO: can we manually read in the stereParams.mat? (probs not)
% T_LtoR = [...
% 1.0000 -0.0021 -0.0036 -0.4751;
% 0.0021 1.0000 0.0046 -0.0011;
% 0.0036 -0.0046 1.0000 0.0020;
% 0 0 0 1.0000;
% ];


% Vehicle2Stereo.txt
% Stereo camera (based on left camera) extrinsic calibration parameter from vehicle
% WHAT????? THEIR POSITION IS INCORRECTLY THE OPOSITE
% DIRECTION????!@#!@#?!@#!@#$!@$%!#@%!#%!~@%!@#%@!#^%#@%^!@#%@#%
p_LinV = [1.66944; 0.278027; 1.61215];
R_LtoV = [-0.00413442 -0.0196634 0.999798; -0.999931 -0.0109505 -0.00435034; 0.0110338 -0.999747 -0.0196168];
% NOTE: This was taken from the Urban28 dataset
% NOTE: The sample_with_img.tar.gz has different calibration (shouldn't be used)
% WHAT????? THEIR POSITION IS INCORRECTLY THE OPOSITE DIRECTION????
p_LinV = [1.64239; 0.247401; 1.58411];
R_LtoV = [-0.00680499 -0.0153215 0.99985; -0.999977 0.000334627 -0.00680066; -0.000230383 -0.999883 -0.0153234];
T_VtoL = [...
R_LtoV' -R_LtoV'*p_LinV;
0 0 0 1
Expand All @@ -50,7 +53,6 @@
];



% calculate the transform between the camneras and the IMU
T_LtoI = T_VtoI*inv(T_VtoL);
T_RtoI = T_VtoI*inv(T_LtoR*T_VtoL);
Expand Down
4 changes: 2 additions & 2 deletions ov_msckf/launch/serial.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,14 @@

<!-- what config we are going to run (should match folder name) -->
<arg name="verbosity" default="INFO" /> <!-- ALL, DEBUG, INFO, WARNING, ERROR, SILENT -->
<arg name="config" default="euroc_mav" /> <!-- euroc_mav, tum_vi, rpng_aruco -->
<arg name="config" default="euroc_mav" /> <!-- euroc_mav, tum_vi, rpng_aruco, kaist -->
<arg name="config_path" default="$(find ov_msckf)/../config/$(arg config)/estimator_config.yaml" />

<!-- mono or stereo and what ros bag to play -->
<arg name="max_cameras" default="2" />
<arg name="use_stereo" default="true" />
<arg name="bag_start" default="0" /> <!-- v1-2: 0, mh1: 40, mh2: 35, mh3: 17.5, mh4-5: 15 -->
<arg name="dataset" default="V2_02_medium" /> <!-- V1_01_easy, V1_02_medium, V1_03_difficult, V2_02_medium, dataset-room1_512_16 -->
<arg name="dataset" default="V1_02_medium" /> <!-- V1_01_easy, V1_02_medium, V1_03_difficult, V2_02_medium, dataset-room1_512_16 -->
<arg name="bag" default="/media/patrick/RPNG FLASH 3/$(arg config)/$(arg dataset).bag" />
<!-- <arg name="bag" default="/home/patrick/datasets/$(arg config)/$(arg dataset).bag" /> -->
<!-- <arg name="bag" default="/datasets/$(arg config)/$(arg dataset).bag" /> -->
Expand Down

0 comments on commit d171a03

Please sign in to comment.