Skip to content
Permalink

Comparing changes

Choose two branches to see what’s changed or to start a new pull request. If you need to, you can also or learn more about diff comparisons.

Open a pull request

Create a new pull request by comparing changes across two branches. If you need to, you can also . Learn more about diff comparisons here.
base repository: HKUST-Aerial-Robotics/VINS-Mono
Failed to load repositories. Confirm that selected base ref is valid, then try again.
Loading
base: master
Choose a base ref
...
head repository: arl-kgp/VINS-Mono
Failed to load repositories. Confirm that selected head ref is valid, then try again.
Loading
compare: master
Choose a head ref
Can’t automatically merge. Don’t worry, you can still create the pull request.
  • 2 commits
  • 1 file changed
  • 1 contributor

Commits on Jul 21, 2018

  1. Copy the full SHA
    a2e4322 View commit details

Commits on Jul 22, 2018

  1. IMU variances, Vibration dampning with better props and gimbal dampne…

    …r: Works on Albatross!
    mpdmanash committed Jul 22, 2018
    Copy the full SHA
    164d687 View commit details
Showing with 20 additions and 17 deletions.
  1. +20 −17 config/euroc/euroc_config.yaml
37 changes: 20 additions & 17 deletions config/euroc/euroc_config.yaml
Original file line number Diff line number Diff line change
@@ -2,24 +2,24 @@

#common parameters
imu_topic: "/imu0"
image_topic: "/cam0/image_raw"
output_path: "/home/tony-ws1/output/"
image_topic: "/camera/left/image_raw"
output_path: "/home/manash/output/"

#camera calibration
model_type: PINHOLE
camera_name: camera
image_width: 752
image_height: 480
distortion_parameters:
k1: -2.917e-01
k2: 8.228e-02
p1: 5.333e-05
p2: -1.578e-04
k1: -0.351508
k2: 0.088678
p1: 0.000176
p2: -0.000472
projection_parameters:
fx: 4.616e+02
fy: 4.603e+02
cx: 3.630e+02
cy: 2.481e+02
fx: 457.514038
fy: 457.787703
cx: 370.395692
cy: 250.884523

# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
@@ -31,15 +31,18 @@ extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.0148655429818, -0.999880929698, 0.00414029679422,
0.999557249008, 0.0149672133247, 0.025715529948,
-0.0257744366974, 0.00375618835797, 0.999660727178]
# data: [-1.0000000, -0.0000000, 0.0000000,
# 0.0000000, -1.0000000, 0.0000000,
# 0.0000000, 0.0000000, 1.0000000]
data: [-0.985818, 0.157594, 0.0576817,
-0.156092, -0.987296, 0.0297032,
0.0616299, 0.0202783, 0.997893]
#Translation from camera frame to imu frame, imu^T_cam
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [-0.0216401454975,-0.064676986768, 0.00981073058949]
data: [0.07014, -0.0014, 0.00738]

#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
@@ -56,8 +59,8 @@ 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.08 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_n: 0.4 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.1 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.00004 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-6 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.81007 # gravity magnitude
@@ -77,6 +80,6 @@ rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutt
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).

#visualization parameters
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ