Skip to content

Commit

Permalink
Merge pull request ethz-asl#46 from ethz-asl/fix/canditateGenerationH
Browse files Browse the repository at this point in the history
quick fix, also changed discriminativeSamplingGain to be better for l…
  • Loading branch information
bloesch committed Mar 15, 2016
2 parents f1abf0b + 37453e6 commit e148e13
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 14 deletions.
24 changes: 12 additions & 12 deletions cfg/rovio.info
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ Init
gyb_0 3e-4; X-Covariance of initial gyroscope bias [rad^2/s^2]
gyb_1 3e-4; Y-Covariance of initial gyroscope bias [rad^2/s^2]
gyb_2 3e-4; Z-Covariance of initial gyroscope bias [rad^2/s^2]
vep 0.01; Covariance of initial linear camera-IMU extrinsics, same for all entries [m^2]
vep 0.0001; Covariance of initial linear camera-IMU extrinsics, same for all entries [m^2]
att_0 0.1; X-Covariance of initial attitude [rad^2]
att_1 0.1; Y-Covariance of initial attitude [rad^2]
att_2 0.1; Z-Covariance of initial attitude [rad^2]
Expand All @@ -81,13 +81,13 @@ ImgUpdate
startLevel 2; Highest patch level which is being employed (must be smaller than the hardcoded template parameter)
endLevel 1; Lowest patch level which is being employed
nDetectionBuckets 100; Number of discretization buckets used during the candidates selection
MahalanobisTh 2.21; Mahalanobis treshold for the update, 5.8858356
MahalanobisTh 9.21; Mahalanobis treshold for the update, 5.8858356
UpdateNoise
{
pix 2; Covariance used for the reprojection error, 1/focal_length is roughly 1 pixel std [rad] (~1/f ~ 1/400^2 = 1/160000)
int 10000; Covariance used for the photometric error [intensity^2]
int 400; Covariance used for the photometric error [intensity^2]
}
initCovFeature_0 2.0; Covariance for the initial distance (Relative to initialization depth [m^2/m^2])
initCovFeature_0 4.0; Covariance for the initial distance (Relative to initialization depth [m^2/m^2])
initCovFeature_1 1e-5; Covariance for the initial bearing vector, x-component [rad^2]
initCovFeature_2 1e-5; Covariance for the initial bearing vector, y-component [rad^2]
initDepth 0.5; Initial value for the initial distance parameter
Expand All @@ -110,7 +110,7 @@ ImgUpdate
alignCoverageRatio 2; How many sigma of the uncertainty should be covered in the adaptive alignement
alignMaxUniSample 1; Maximal number of alignment seeds on one side -> total number of sample = 2n+1. Carefull can get very costly if diverging!
patchRejectionTh 50.0; If the average itensity error is larger than this the feauture is rejected [intensity], if smaller 0 the no check is performed
alignmentHuberNormThreshold -1; Intensity error threshold for Huber norm (enabled if > 0)
alignmentHuberNormThreshold 10; Intensity error threshold for Huber norm (enabled if > 0)
alignmentGaussianWeightingSigma -1; Width of Gaussian which is used for pixel error weighting (enabled if > 0)
alignmentGradientExponent 0.0; Exponent used for gradient based weighting of residuals
useIntensityOffsetForAlignment true; Should an intensity offset between the patches be considered
Expand All @@ -121,7 +121,7 @@ ImgUpdate
doStereoInitialization true; Should a stereo match be used for feature initialization.
noiseGainForOffCamera 10.0; Factor added on update noise if not main camera
discriminativeSamplingDistance 0.02; Sampling distance for checking discriminativity of patch (if <= 0.0 no check is performed).
discriminativeSamplingGain 2.0; Gain for threshold above which the samples must lie (if <= 1.0 the patchRejectionTh is used).
discriminativeSamplingGain 1.1; Gain for threshold above which the samples must lie (if <= 1.0 the patchRejectionTh is used).
MotionDetection
{
isEnabled 0; Is the motion detection enabled
Expand Down Expand Up @@ -149,19 +149,19 @@ Prediction
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-4; 4e-6 X-covariance parameter of velocity prediction [m^2/s^3]
vel_1 4e-4; Y-covariance parameter of velocity prediction [m^2/s^3]
vel_2 4e-4; Z-covariance parameter of velocity prediction [m^2/s^3]
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 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-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]
att_0 7.6e-7; 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]
Expand Down
4 changes: 2 additions & 2 deletions include/rovio/ImgUpdate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ ImgOutlierDetection<typename FILTERSTATE::mtState>,false>{
pixelOutputCov_((int)(PixelOutput::D_),(int)(PixelOutput::D_)),
featureOutputCov_((int)(FeatureOutput::D_),(int)(FeatureOutput::D_)),
featureOutputJac_((int)(FeatureOutput::D_),(int)(mtState::D_)),
canditateGenerationH_((int)(mtState::D_),2),
canditateGenerationH_(2,(int)(mtState::D_)),
canditateGenerationDifVec_((int)(mtState::D_),1),
canditateGenerationPy_(2,2){
mpMultiCamera_ = nullptr;
Expand Down Expand Up @@ -452,7 +452,7 @@ ImgOutlierDetection<typename FILTERSTATE::mtState>,false>{
transformFeatureOutputCT_.jacTransform(featureOutputJac_,candidate);
mpMultiCamera_->cameras_[activeCamID].bearingToPixel(featureOutput_.c().get_nor(),c_temp_,c_J_);

canditateGenerationH_ = c_J_*featureOutputJac_.template block<2,mtState::D_>(0,0);
canditateGenerationH_ = -c_J_*featureOutputJac_.template block<2,mtState::D_>(0,0);
canditateGenerationPy_ = canditateGenerationH_*filterState.cov_*canditateGenerationH_.transpose();
candidateGenerationES_.compute(canditateGenerationPy_);
}
Expand Down

0 comments on commit e148e13

Please sign in to comment.