Skip to content

Commit 6c0d84f

Browse files
committed
tro revision param
1 parent 27aa727 commit 6c0d84f

File tree

5 files changed

+14
-14
lines changed

5 files changed

+14
-14
lines changed

config/euroc/euroc_config.yaml

+9-9
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ projection_parameters:
2222
cy: 2.481e+02
2323

2424
# Extrinsic parameter between IMU and Camera.
25-
estimate_extrinsic: 1 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
25+
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
2626
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
2727
# 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.
2828
#If you choose 0 or 1, you should write down the following matrix.
@@ -31,15 +31,15 @@ extrinsicRotation: !!opencv-matrix
3131
rows: 3
3232
cols: 3
3333
dt: d
34-
data: [0, -1, 0,
35-
1, 0, 0,
36-
0, 0, 1]
34+
data: [0.0148655429818, -0.999880929698, 0.00414029679422,
35+
0.999557249008, 0.0149672133247, 0.025715529948,
36+
-0.0257744366974, 0.00375618835797, 0.999660727178]
3737
#Translation from camera frame to imu frame, imu^T_cam
3838
extrinsicTranslation: !!opencv-matrix
3939
rows: 3
4040
cols: 1
4141
dt: d
42-
data: [-0.02,-0.06, 0.01]
42+
data: [-0.0216401454975,-0.064676986768, 0.00981073058949]
4343

4444
#feature traker paprameters
4545
max_cnt: 150 # max feature number in feature tracking
@@ -56,10 +56,10 @@ max_num_iterations: 8 # max solver itrations, to guarantee real time
5656
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
5757

5858
#imu parameters The more accurate parameters you provide, the better performance
59-
acc_n: 0.2 # accelerometer measurement noise standard deviation. #0.2
60-
gyr_n: 0.02 # gyroscope measurement noise standard deviation. #0.05
61-
acc_w: 0.0002 # accelerometer bias random work noise standard deviation. #0.02
62-
gyr_w: 2.0e-5 # gyroscope bias random work noise standard deviation. #4.0e-5
59+
acc_n: 0.08 # accelerometer measurement noise standard deviation. #0.2 0.04
60+
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
61+
acc_w: 0.00004 # accelerometer bias random work noise standard deviation. #0.02
62+
gyr_w: 2.0e-6 # gyroscope bias random work noise standard deviation. #4.0e-5
6363
g_norm: 9.81007 # gravity magnitude
6464

6565
#loop closure parameters

config/realsense/realsense_color_config.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -70,10 +70,10 @@ pose_graph_save_path: "/home/tony-ws1/output/pose_graph/" # save and load path
7070

7171
#unsynchronization parameters
7272
estimate_td: 1 # online estimate time offset between camera and imu
73-
td: 0.007 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
73+
td: 0.000 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
7474

7575
#rolling shutter parameters
76-
rolling_shutter: 1 # 0: global shutter camera, 1: rolling shutter camera
76+
rolling_shutter: 1 # 0: global shutter camera, 1: rolling shutter camera
7777
rolling_shutter_tr: 0.033 # unit: s. rolling shutter read out time per frame (from data sheet).
7878

7979
#visualization parameters

config/realsense/realsense_fisheye_config.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ min_dist: 30 # min distance between two features
4949
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
5050
F_threshold: 1.0 # ransac threshold (pixel)
5151
show_track: 1 # publish tracking image as topic
52-
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
52+
equalize: 0 # if image is too dark or light, trun on equalize to find enough features
5353
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
5454

5555
#optimization parameters

pose_graph/src/pose_graph.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -437,7 +437,7 @@ void PoseGraph::optimize4DoF()
437437
options.max_num_iterations = 5;
438438
ceres::Solver::Summary summary;
439439
ceres::LossFunction *loss_function;
440-
loss_function = new ceres::HuberLoss(1.0);
440+
loss_function = new ceres::HuberLoss(0.1);
441441
//loss_function = new ceres::CauchyLoss(1.0);
442442
ceres::LocalParameterization* angle_local_parameterization =
443443
AngleLocalParameterization::Create();

pose_graph/src/pose_graph.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -204,7 +204,7 @@ struct FourDOFWeightError
204204
{
205205
FourDOFWeightError(double t_x, double t_y, double t_z, double relative_yaw, double pitch_i, double roll_i)
206206
:t_x(t_x), t_y(t_y), t_z(t_z), relative_yaw(relative_yaw), pitch_i(pitch_i), roll_i(roll_i){
207-
weight = 1;
207+
weight = 0.1;
208208
}
209209

210210
template <typename T>

0 commit comments

Comments
 (0)