forked from HKUST-Aerial-Robotics/VINS-Mono
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
2aefe31
commit 491652e
Showing
2 changed files
with
91 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,76 @@ | ||
%YAML:1.0 | ||
|
||
#common parameters | ||
imu_topic: "/imu0" | ||
image_topic: "/cam0/image_raw" | ||
output_path: "/config/loitor/vins_result.csv" # vins outputs will be wrttento vins_folder_path + output_path | ||
|
||
#camera calibration | ||
model_type: MEI | ||
camera_name: camera | ||
image_width: 752 | ||
image_height: 480 | ||
mirror_parameters: | ||
xi: 5.9080254303887356e+00 | ||
distortion_parameters: | ||
k1: -9.7010482866651282e-01 | ||
k2: 9.0854285568221620e+00 | ||
p1: -8.8740061896374900e-03 | ||
p2: 1.4867641178997661e-04 | ||
projection_parameters: | ||
gamma1: 3.2367070160240969e+03 | ||
gamma2: 3.2362264175627506e+03 | ||
u0: 3.9905044304547499e+02 | ||
v0: 2.2092609726522585e+02 | ||
|
||
# Extrinsic parameter between IMU and Camera. | ||
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it. | ||
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess. | ||
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning. | ||
ex_calib_result_path: "/config/loitor/ex_calib_result.yaml" # If you choose 1 or 2, the extrinsic calibration result will be written vins_folder_path + ex_calib_result_path. | ||
#If you choose 0 or 1, you should write down the following matrix. | ||
#Rotation from camera frame to imu frame, imu^R_cam | ||
extrinsicRotation: !!opencv-matrix | ||
rows: 3 | ||
cols: 3 | ||
dt: d | ||
data: [0, -1, 0, | ||
-1, 0, 0, | ||
0, 0, -1] | ||
#Translation from camera frame to imu frame, imu^T_cam | ||
extrinsicTranslation: !!opencv-matrix | ||
rows: 3 | ||
cols: 1 | ||
dt: d | ||
data: [-0.01, 0.05, 0.00] | ||
|
||
#feature traker paprameters | ||
max_cnt: 150 # max feature number in feature tracking | ||
min_dist: 30 # min distance between two features | ||
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image | ||
F_threshold: 1.0 # ransac threshold (pixel) | ||
show_track: 1 # publish tracking image as topic | ||
equalize: 0 # if image is too dark or light, trun on equalize to find enough features | ||
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points | ||
|
||
#optimization parameters | ||
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time | ||
max_num_iterations: 8 # max solver itrations, to guarantee real time | ||
keyframe_parallax: 10.0 # keyframe selection threshold (pixel) | ||
|
||
#imu parameters The more accurate parameters you provide, the better performance | ||
acc_n: 0.2 # accelerometer measurement noise standard deviation. #0.2 | ||
gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05 | ||
acc_w: 0.002 # accelerometer bias random work noise standard deviation. #0.02 | ||
gyr_w: 2.0e-4 # gyroscope bias random work noise standard deviation. #4.0e-5 | ||
g_norm: 9.81007 # gravity magnitude | ||
|
||
|
||
#loop closure parameters | ||
loop_closure: 0 #if you want to use loop closure to minimize the drift, set loop_closure true and give your brief pattern file path and vocabulary file path accordingly; | ||
#also give the camera calibration file same as feature_tracker node | ||
pattern_file: "/support_files/brief_pattern.yml" | ||
voc_file: "/support_files/brief_k10L6.bin" | ||
min_loop_num: 25 | ||
|
||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,15 @@ | ||
<launch> | ||
<arg name="config_path" default = "$(find feature_tracker)/../config/loitor/loitor_config.yaml" /> | ||
<arg name="vins_path" default = "$(find feature_tracker)/../config/../" /> | ||
|
||
<node name="feature_tracker" pkg="feature_tracker" type="feature_tracker" output="log"> | ||
<param name="config_file" type="string" value="$(arg config_path)" /> | ||
<param name="vins_folder" type="string" value="$(arg vins_path)" /> | ||
</node> | ||
|
||
<node name="vins_estimator" pkg="vins_estimator" type="vins_estimator" output="screen"> | ||
<param name="config_file" type="string" value="$(arg config_path)" /> | ||
<param name="vins_folder" type="string" value="$(arg vins_path)" /> | ||
</node> | ||
|
||
</launch> |