Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Devel/multi cam #203

Open
wants to merge 35 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
35 commits
Select commit Hold shift + click to select a range
1a3a198
launch and cfg files for RealSense and px4
Jun 18, 2018
4073537
calibration file for RealSense D435
Jun 20, 2018
b5fe5bd
launch cleanup
Jun 21, 2018
d514671
config file for downward IMU-cam configuration
Jun 25, 2018
863a40a
info file for downward configuration
Jun 25, 2018
8b191a4
name cleanup
Jun 25, 2018
747350a
cfg folder cleanup
Jun 25, 2018
b5f7c6a
setup for M600
Jun 28, 2018
19d148c
M600 calibration files
Jun 28, 2018
e343156
update for domi sensor
Oct 23, 2018
513c94c
clean up
Oct 23, 2018
bc0b2b0
rovio with three cameras working
Nov 19, 2018
ede5a47
Merge branch 'dev-multiCam' of https://github.com/Auterion/auterion_r…
Nov 19, 2018
f55ff7a
up to five cam setup
Nov 20, 2018
53e394d
added histogram equalization
Nov 28, 2018
8de80e4
added histogram equalization
Dec 3, 2018
0367a40
visualization of candidates
Dec 3, 2018
3002088
health checker added
Dec 10, 2018
e4c2001
add best global features
Dec 12, 2018
6a6ad37
addGlobalBest param added
Dec 12, 2018
08bc0ac
new param for info file: HE, HC, addGlobal, showCandidates
Dec 12, 2018
3039c53
updated camera order to match order in rovio_domi.launch
Jan 31, 2019
a0cfab9
clean up: removal of old files
Jan 31, 2019
ffd0564
clean up remove old files
Feb 1, 2019
f1de7bc
clean up
Oct 23, 2018
0c91a53
up to five cam setup
Nov 20, 2018
e62b660
added histogram equalization
Nov 28, 2018
735a8bb
added histogram equalization
Dec 3, 2018
896873c
visualization of candidates
Dec 3, 2018
13309d8
health checker added
Dec 10, 2018
63d2fb2
add best global features
Dec 12, 2018
c818080
addGlobalBest param added
Dec 12, 2018
2ec4fce
new param for info file: HE, HC, addGlobal, showCandidates
Dec 12, 2018
a507af4
updated camera order to match order in rovio_domi.launch
Jan 31, 2019
664f813
Merge branch 'devel/multi_cam' of https://github.com/trleonie/rovio i…
Feb 1, 2019
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions cfg/domi_cam0.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
image_width: 752
image_height: 480
camera_name: cam0
camera_matrix:
rows: 3
cols: 3
data: [393.016201519, 0.0, 360.133022189, 0.0, 392.357540103, 239.827503562, 0.0, 0.0, 1.0]
distortion_model: equidistant
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0524237801608, -0.00545225097947, -0.00275082473186, 0.00117687962781]

13 changes: 13 additions & 0 deletions cfg/domi_cam1.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
image_width: 752
image_height: 480
camera_name: cam1
camera_matrix:
rows: 3
cols: 3
data: [399.348057011, 0.0, 386.463445149, 0.0, 398.349131629, 249.821188712, 0.0, 0.0, 1.0]
distortion_model: equidistant
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0577566077926, -0.0163210986871, 0.0108510337124, -0.00372778210309]

13 changes: 13 additions & 0 deletions cfg/domi_cam2.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
image_width: 752
image_height: 480
camera_name: cam2
camera_matrix:
rows: 3
cols: 3
data: [401.647215983, 0.0, 364.57630651, 0.0, 400.20768313, 237.330914431, 0.0, 0.0, 1.0]
distortion_model: equidistant
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0645622778177, -0.0139883244162, 0.0160581204973, -0.00758677666188]

13 changes: 13 additions & 0 deletions cfg/domi_cam3.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
image_width: 752
image_height: 480
camera_name: cam3
camera_matrix:
rows: 3
cols: 3
data: [398.9944782, 0.0, 364.41599021, 0.0, 398.080578743, 275.477777432, 0.0, 0.0, 1.0]
distortion_model: equidistant
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0560625387897, -0.014037695708, 0.00638405850267, -0.00151939229656]

13 changes: 13 additions & 0 deletions cfg/domi_cam4.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
image_width: 752
image_height: 480
camera_name: cam4
camera_matrix:
rows: 3
cols: 3
data: [400.103070384, 0.0, 371.400642253, 0.0, 399.068157312, 248.047178007, 0.0, 0.0, 1.0]
distortion_model: equidistant
distortion_coefficients:
rows: 1
cols: 4
data: [-0.0586905828624, -0.00419400201291, -0.00142056808843, 0.000320459725526]

23 changes: 0 additions & 23 deletions cfg/euroc_cam0.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,26 +12,3 @@ distortion_coefficients:
cols: 5
data: [-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]

###### Original Calibration File ######
## General sensor definitions.
#sensor_type: camera
#comment: VI-Sensor cam0 (MT9M034)
#
## Sensor extrinsics wrt. the body-frame.
#T_BS:
# cols: 4
# rows: 4
# data: [0.0148655429818, -0.999880929698, 0.00414029679422, -0.0216401454975,
# 0.999557249008, 0.0149672133247, 0.025715529948, -0.064676986768,
# -0.0257744366974, 0.00375618835797, 0.999660727178, 0.00981073058949,
# 0.0, 0.0, 0.0, 1.0]
#
## Camera specific definitions.
#rate_hz: 20
#resolution: [752, 480]
#camera_model: pinhole
#intrinsics: [458.654, 457.296, 367.215, 248.375] #fu, fv, cu, cv
#distortion_model: radial-tangential
#distortion_coefficients: [-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05]


13 changes: 13 additions & 0 deletions cfg/euroc_cam0_new.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
###### Camera Calibration File For Cam 0 of Euroc Datasets ######
image_width: 752
image_height: 480
camera_name: cam0
camera_matrix:
rows: 3
cols: 3
data: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0]
10 changes: 10 additions & 0 deletions cfg/imu.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#Accelerometers
accelerometer_noise_density: 1.86e-03 #Noise density (continuous-time)
accelerometer_random_walk: 4.33e-04 #Bias random walk

#Gyroscopes
gyroscope_noise_density: 1.87e-04 #Noise density (continuous-time)
gyroscope_random_walk: 2.66e-05 #Bias random walk

rostopic: /mavros/imu/data #the IMU ROS topic
update_rate: 200.0 #Hz (for discretization of the values above)
68 changes: 35 additions & 33 deletions cfg/rovio.info
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,14 @@ Common
}
Camera0
{
CalibrationFile ; Camera-Calibration file for intrinsics
qCM_x 0.00666398307551; X-entry of IMU to Camera quaterion (Hamilton)
qCM_y -0.0079168224269; Y-entry of IMU to Camera quaterion (Hamilton)
qCM_z -0.701985972528; Z-entry of IMU to Camera quaterion (Hamilton)
qCM_w 0.712115587266; W-entry of IMU to Camera quaterion (Hamilton)
MrMC_x -0.0111674199187; X-entry of IMU to Camera vector (expressed in IMU CF) [m]
MrMC_y -0.0574640920022; Y-entry of IMU to Camera vector (expressed in IMU CF) [m]
MrMC_z 0.0207586947896; Z-entry of IMU to Camera vector (expressed in IMU CF) [m]
CalibrationFile ; Camera-Calibration file for intrinsics
qCM_x 0.498529507038; X-entry of IMU to Camera quaterion (Hamilton)
qCM_y -0.496012173235; Y-entry of IMU to Camera quaterion (Hamilton)
qCM_z 0.511762063883; Z-entry of IMU to Camera quaterion (Hamilton)
qCM_w 0.493497562897; W-entry of IMU to Camera quaterion (Hamilton)
MrMC_x 0.000218693879012; X-entry of IMU to Camera vector (expressed in IMU CF) [m]
MrMC_y -0.00011610537335; Y-entry of IMU to Camera vector (expressed in IMU CF) [m]
MrMC_z -0.000499672135095; Z-entry of IMU to Camera vector (expressed in IMU CF) [m]
}
Camera1
{
Expand Down Expand Up @@ -146,31 +146,33 @@ Prediction
{
PredictionNoise
{
pos_0 1e-4; X-covariance parameter of position prediction [m^2/s]
pos_1 1e-4; Y-covariance parameter of position prediction [m^2/s]
pos_2 1e-4; Z-covariance parameter of position prediction [m^2/s]
vel_0 4e-6; X-covariance parameter of velocity prediction [m^2/s^3]
vel_1 4e-6; Y-covariance parameter of velocity prediction [m^2/s^3]
vel_2 4e-6; Z-covariance parameter of velocity prediction [m^2/s^3]
acb_0 1e-8; X-covariance parameter of accelerometer bias prediction [m^2/s^5]
acb_1 1e-8; Y-covariance parameter of accelerometer bias prediction [m^2/s^5]
acb_2 1e-8; Z-covariance parameter of accelerometer bias prediction [m^2/s^5]
gyb_0 3.8e-7; X-covariance parameter of gyroscope bias prediction [rad^2/s^3]
gyb_1 3.8e-7; Y-covariance parameter of gyroscope bias prediction [rad^2/s^3]
gyb_2 3.8e-7; Z-covariance parameter of gyroscope bias prediction [rad^2/s^3]
vep 1e-8; Covariance parameter of linear extrinsics prediction [m^2/s]
att_0 7.6e-7; X-Covariance parameter of attitude prediction [rad^2/s]
att_1 7.6e-7; Y-Covariance parameter of attitude prediction [rad^2/s]
att_2 7.6e-7; Z-Covariance parameter of attitude prediction [rad^2/s]
vea 1e-8; Covariance parameter of rotational extrinsics prediction [rad^2/s]
dep 0.0001; Covariance parameter of distance prediction [m^2/s]
nor 0.00001; Covariance parameter of bearing vector prediction [rad^2/s]
pos_0 1e-4; X-covariance parameter of position prediction [m^2/s]
pos_1 1e-4; Y-covariance parameter of position prediction [m^2/s]
pos_2 1e-4; Z-covariance parameter of position prediction [m^2/s]
vel_0 4e-5; 4e-6 X-covariance parameter of velocity prediction [m^2/s^3]
vel_1 4e-5; Y-covariance parameter of velocity prediction [m^2/s^3]
vel_2 4e-5; Z-covariance parameter of velocity prediction [m^2/s^3]
acb_0 9e-6; X-covariance parameter of accelerometer bias prediction [m^2/s^5]
acb_1 9e-6; Y-covariance parameter of accelerometer bias prediction [m^2/s^5]
acb_2 9e-6; Z-covariance parameter of accelerometer bias prediction [m^2/s^5]
gyb_0 2e-8; X-covariance parameter of gyroscope bias prediction [rad^2/s^3]
gyb_1 2e-8; Y-covariance parameter of gyroscope bias prediction [rad^2/s^3]
gyb_2 2e-8; Z-covariance parameter of gyroscope bias prediction [rad^2/s^3]
vep 1e-6; Covariance parameter of linear extrinsics prediction [m^2/s]
att_0 7.6e-6; 7.6e-7 X-Covariance parameter of attitude prediction [rad^2/s]
att_1 7.6e-6; Y-Covariance parameter of attitude prediction [rad^2/s]
att_2 7.6e-6; Z-Covariance parameter of attitude prediction [rad^2/s]
vea 1e-6; Covariance parameter of rotational extrinsics prediction [rad^2/s]
dep 0.0001; Covariance parameter of distance prediction [m^2/s]
nor 0.00001; Covariance parameter of bearing vector prediction [rad^2/s]


}
MotionDetection
{
inertialMotionRorTh 0.1; Treshold on rotational rate for motion detection [rad/s]
inertialMotionAccTh 0.5; Treshold on acceleration for motion detection [m/s^2]
}
inertialMotionRorTh 0.1; Treshold on rotational rate for motion detection [rad/s]
inertialMotionAccTh 0.5; Treshold on acceleration for motion detection [m/s^2]
}
}
PoseUpdate
{
Expand Down Expand Up @@ -202,14 +204,14 @@ PoseUpdate
qVM_x 0; X-entry of quaterion representing IMU to reference body coordinate frame of pose measurement (Hamilton)
qVM_y 0; Y-entry of quaterion representing IMU to reference body coordinate frame of pose measurement (Hamilton)
qVM_z 0; Z-entry of quaterion representing IMU to reference body coordinate frame of pose measurement (Hamilton)
qVM_w 1; W-entry of quaterion representing IMU to reference body coordinate frame of pose measurement (Hamilton)
qVM_w -1; W-entry of quaterion representing IMU to reference body coordinate frame of pose measurement (Hamilton)
MrMV_x 0; X-entry of vector representing IMU to reference body coordinate frame of pose measurement
MrMV_y 0; Y-entry of vector representing IMU to reference body coordinate frame of pose measurement
MrMV_z 0; Z-entry of vector representing IMU to reference body coordinate frame of pose measurement
qWI_x 0; X-entry of quaterion representing World to reference inertial coordinate frame of pose measurement (Hamilton)
qWI_y 0; Y-entry of quaterion representing World to reference inertial coordinate frame of pose measurement (Hamilton)
qWI_z 0; Z-entry of quaterion representing World to reference inertial coordinate frame of pose measurement (Hamilton)
qWI_w 1; W-entry of quaterion representing World to reference inertial coordinate frame of pose measurement (Hamilton)
qWI_w -1; W-entry of quaterion representing World to reference inertial coordinate frame of pose measurement (Hamilton)
IrIW_x 0; X-entry of vector representing World to reference inertial coordinate frame of pose measurement
IrIW_y 0; Y-entry of vector representing World to reference inertial coordinate frame of pose measurement
IrIW_z 0; Z-entry of vector representing World to reference inertial coordinate frame of pose measurement
Expand All @@ -227,4 +229,4 @@ VelocityUpdate
qAM_y 0
qAM_z 0
qAM_w 1
}
}
Loading