00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include "robot_localization/ekf.h"
00034 #include "robot_localization/filter_common.h"
00035
00036 #include <XmlRpcException.h>
00037
00038 #include <sstream>
00039 #include <iomanip>
00040 #include <limits>
00041
00042 namespace RobotLocalization
00043 {
00044 Ekf::Ekf(std::vector<double>) :
00045 FilterBase()
00046 {
00047 }
00048
00049 Ekf::~Ekf()
00050 {
00051 }
00052
00053 void Ekf::correct(const Measurement &measurement)
00054 {
00055 FB_DEBUG("---------------------- Ekf::correct ----------------------\n" <<
00056 "State is:\n" << state_ << "\n"
00057 "Topic is:\n" << measurement.topicName_ << "\n"
00058 "Measurement is:\n" << measurement.measurement_ << "\n"
00059 "Measurement topic name is:\n" << measurement.topicName_ << "\n\n"
00060 "Measurement covariance is:\n" << measurement.covariance_ << "\n");
00061
00062
00063
00064
00065
00066
00067 std::vector<size_t> updateIndices;
00068 for (size_t i = 0; i < measurement.updateVector_.size(); ++i)
00069 {
00070 if (measurement.updateVector_[i])
00071 {
00072
00073 if (std::isnan(measurement.measurement_(i)))
00074 {
00075 FB_DEBUG("Value at index " << i << " was nan. Excluding from update.\n");
00076 }
00077 else if (std::isinf(measurement.measurement_(i)))
00078 {
00079 FB_DEBUG("Value at index " << i << " was inf. Excluding from update.\n");
00080 }
00081 else
00082 {
00083 updateIndices.push_back(i);
00084 }
00085 }
00086 }
00087
00088 FB_DEBUG("Update indices are:\n" << updateIndices << "\n");
00089
00090 size_t updateSize = updateIndices.size();
00091
00092
00093 Eigen::VectorXd stateSubset(updateSize);
00094 Eigen::VectorXd measurementSubset(updateSize);
00095 Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize);
00096 Eigen::MatrixXd stateToMeasurementSubset(updateSize, state_.rows());
00097 Eigen::MatrixXd kalmanGainSubset(state_.rows(), updateSize);
00098 Eigen::VectorXd innovationSubset(updateSize);
00099
00100 stateSubset.setZero();
00101 measurementSubset.setZero();
00102 measurementCovarianceSubset.setZero();
00103 stateToMeasurementSubset.setZero();
00104 kalmanGainSubset.setZero();
00105 innovationSubset.setZero();
00106
00107
00108 for (size_t i = 0; i < updateSize; ++i)
00109 {
00110 measurementSubset(i) = measurement.measurement_(updateIndices[i]);
00111 stateSubset(i) = state_(updateIndices[i]);
00112
00113 for (size_t j = 0; j < updateSize; ++j)
00114 {
00115 measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]);
00116 }
00117
00118
00119
00120
00121 if (measurementCovarianceSubset(i, i) < 0)
00122 {
00123 FB_DEBUG("WARNING: Negative covariance for index " << i <<
00124 " of measurement (value is" << measurementCovarianceSubset(i, i) <<
00125 "). Using absolute value...\n");
00126
00127 measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i));
00128 }
00129
00130
00131
00132
00133
00134
00135
00136 if (measurementCovarianceSubset(i, i) < 1e-9)
00137 {
00138 FB_DEBUG("WARNING: measurement had very small error covariance for index " << updateIndices[i] <<
00139 ". Adding some noise to maintain filter stability.\n");
00140
00141 measurementCovarianceSubset(i, i) = 1e-9;
00142 }
00143 }
00144
00145
00146
00147 for (size_t i = 0; i < updateSize; ++i)
00148 {
00149 stateToMeasurementSubset(i, updateIndices[i]) = 1;
00150 }
00151
00152 FB_DEBUG("Current state subset is:\n" << stateSubset <<
00153 "\nMeasurement subset is:\n" << measurementSubset <<
00154 "\nMeasurement covariance subset is:\n" << measurementCovarianceSubset <<
00155 "\nState-to-measurement subset is:\n" << stateToMeasurementSubset << "\n");
00156
00157
00158 Eigen::MatrixXd pht = estimateErrorCovariance_ * stateToMeasurementSubset.transpose();
00159 Eigen::MatrixXd hphrInv = (stateToMeasurementSubset * pht + measurementCovarianceSubset).inverse();
00160 kalmanGainSubset.noalias() = pht * hphrInv;
00161
00162 innovationSubset = (measurementSubset - stateSubset);
00163
00164
00165 if (checkMahalanobisThreshold(innovationSubset, hphrInv, measurement.mahalanobisThresh_))
00166 {
00167
00168
00169 for (size_t i = 0; i < updateSize; ++i)
00170 {
00171 if (updateIndices[i] == StateMemberRoll || updateIndices[i] == StateMemberPitch || updateIndices[i] == StateMemberYaw)
00172 {
00173 while(innovationSubset(i) < -PI)
00174 {
00175 innovationSubset(i) += TAU;
00176 }
00177
00178 while(innovationSubset(i) > PI)
00179 {
00180 innovationSubset(i) -= TAU;
00181 }
00182 }
00183 }
00184
00185 state_.noalias() += kalmanGainSubset * innovationSubset;
00186
00187
00188 Eigen::MatrixXd gainResidual = identity_;
00189 gainResidual.noalias() -= kalmanGainSubset * stateToMeasurementSubset;
00190 estimateErrorCovariance_ = gainResidual * estimateErrorCovariance_ * gainResidual.transpose();
00191 estimateErrorCovariance_.noalias() += kalmanGainSubset * measurementCovarianceSubset * kalmanGainSubset.transpose();
00192
00193
00194 wrapStateAngles();
00195
00196 FB_DEBUG("Kalman gain subset is:\n" << kalmanGainSubset <<
00197 "\nInnovation is:\n" << innovationSubset <<
00198 "\nCorrected full state is:\n" << state_ <<
00199 "\nCorrected full estimate error covariance is:\n" << estimateErrorCovariance_ <<
00200 "\n\n---------------------- /Ekf::correct ----------------------\n");
00201 }
00202 }
00203
00204 void Ekf::predict(const double delta)
00205 {
00206 FB_DEBUG("---------------------- Ekf::predict ----------------------\n" <<
00207 "delta is " << delta << "\n" <<
00208 "state is " << state_ << "\n");
00209
00210 double roll = state_(StateMemberRoll);
00211 double pitch = state_(StateMemberPitch);
00212 double yaw = state_(StateMemberYaw);
00213 double xVel = state_(StateMemberVx);
00214 double yVel = state_(StateMemberVy);
00215 double zVel = state_(StateMemberVz);
00216 double rollVel = state_(StateMemberVroll);
00217 double pitchVel = state_(StateMemberVpitch);
00218 double yawVel = state_(StateMemberVyaw);
00219 double xAcc = state_(StateMemberAx);
00220 double yAcc = state_(StateMemberAy);
00221 double zAcc = state_(StateMemberAz);
00222
00223
00224 double cr = cos(roll);
00225 double cp = cos(pitch);
00226 double cy = cos(yaw);
00227 double sr = sin(roll);
00228 double sp = sin(pitch);
00229 double sy = sin(yaw);
00230
00231
00232 transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta;
00233 transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta;
00234 transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta;
00235 transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta;
00236 transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta;
00237 transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta;
00238 transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta;
00239 transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta;
00240 transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta;
00241 transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta;
00242 transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta;
00243 transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta;
00244 transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta;
00245 transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta;
00246 transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta;
00247 transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta;
00248 transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta;
00249 transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta;
00250 transferFunction_(StateMemberRoll, StateMemberVroll) = transferFunction_(StateMemberX, StateMemberVx);
00251 transferFunction_(StateMemberRoll, StateMemberVpitch) = transferFunction_(StateMemberX, StateMemberVy);
00252 transferFunction_(StateMemberRoll, StateMemberVyaw) = transferFunction_(StateMemberX, StateMemberVz);
00253 transferFunction_(StateMemberPitch, StateMemberVroll) = transferFunction_(StateMemberY, StateMemberVx);
00254 transferFunction_(StateMemberPitch, StateMemberVpitch) = transferFunction_(StateMemberY, StateMemberVy);
00255 transferFunction_(StateMemberPitch, StateMemberVyaw) = transferFunction_(StateMemberY, StateMemberVz);
00256 transferFunction_(StateMemberYaw, StateMemberVroll) = transferFunction_(StateMemberZ, StateMemberVx);
00257 transferFunction_(StateMemberYaw, StateMemberVpitch) = transferFunction_(StateMemberZ, StateMemberVy);
00258 transferFunction_(StateMemberYaw, StateMemberVyaw) = transferFunction_(StateMemberZ, StateMemberVz);
00259 transferFunction_(StateMemberVx, StateMemberAx) = delta;
00260 transferFunction_(StateMemberVy, StateMemberAy) = delta;
00261 transferFunction_(StateMemberVz, StateMemberAz) = delta;
00262
00263
00264
00265 double xCoeff = 0.0;
00266 double yCoeff = 0.0;
00267 double zCoeff = 0.0;
00268 double oneHalfATSquared = 0.5 * delta * delta;
00269
00270 yCoeff = cy * sp * cr + sy * sr;
00271 zCoeff = -cy * sp * sr + sy * cr;
00272 double dF0dr = (yCoeff * yVel + zCoeff * zVel) * delta +
00273 (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00274 double dF6dr = 1 + (yCoeff * rollVel + zCoeff * yawVel) * delta;
00275
00276 xCoeff = -cy * sp;
00277 yCoeff = cy * cp * sr;
00278 zCoeff = cy * cp * cr;
00279 double dF0dp = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +
00280 (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00281 double dF6dp = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;
00282
00283 xCoeff = -sy * cp;
00284 yCoeff = -sy * sp * sr - cy * cr;
00285 zCoeff = -sy * sp * cr + cy * sr;
00286 double dF0dy = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +
00287 (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00288 double dF6dy = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;
00289
00290 yCoeff = sy * sp * cr - cy * sr;
00291 zCoeff = -sy * sp * sr - cy * cr;
00292 double dF1dr = (yCoeff * yVel + zCoeff * zVel) * delta +
00293 (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00294 double dF7dr = (yCoeff * pitchVel + zCoeff * yawVel) * delta;
00295
00296 xCoeff = -sy * sp;
00297 yCoeff = sy * cp * sr;
00298 zCoeff = sy * cp * cr;
00299 double dF1dp = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +
00300 (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00301 double dF7dp = 1 + (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;
00302
00303 xCoeff = cy * cp;
00304 yCoeff = cy * sp * sr - sy * cr;
00305 zCoeff = cy * sp * cr + sy * sr;
00306 double dF1dy = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +
00307 (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00308 double dF7dy = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;
00309
00310 yCoeff = cp * cr;
00311 zCoeff = -cp * sr;
00312 double dF2dr = (yCoeff * yVel + zCoeff * zVel) * delta +
00313 (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00314 double dF8dr = (yCoeff * pitchVel + zCoeff * yawVel) * delta;
00315
00316 xCoeff = -cp;
00317 yCoeff = -sp * sr;
00318 zCoeff = -sp * cr;
00319 double dF2dp = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +
00320 (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;
00321 double dF8dp = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;
00322
00323
00324 transferFunctionJacobian_ = transferFunction_;
00325 transferFunctionJacobian_(StateMemberX, StateMemberRoll) = dF0dr;
00326 transferFunctionJacobian_(StateMemberX, StateMemberPitch) = dF0dp;
00327 transferFunctionJacobian_(StateMemberX, StateMemberYaw) = dF0dy;
00328 transferFunctionJacobian_(StateMemberY, StateMemberRoll) = dF1dr;
00329 transferFunctionJacobian_(StateMemberY, StateMemberPitch) = dF1dp;
00330 transferFunctionJacobian_(StateMemberY, StateMemberYaw) = dF1dy;
00331 transferFunctionJacobian_(StateMemberZ, StateMemberRoll) = dF2dr;
00332 transferFunctionJacobian_(StateMemberZ, StateMemberPitch) = dF2dp;
00333 transferFunctionJacobian_(StateMemberRoll, StateMemberRoll) = dF6dr;
00334 transferFunctionJacobian_(StateMemberRoll, StateMemberPitch) = dF6dp;
00335 transferFunctionJacobian_(StateMemberRoll, StateMemberYaw) = dF6dy;
00336 transferFunctionJacobian_(StateMemberPitch, StateMemberRoll) = dF7dr;
00337 transferFunctionJacobian_(StateMemberPitch, StateMemberPitch) = dF7dp;
00338 transferFunctionJacobian_(StateMemberPitch, StateMemberYaw) = dF7dy;
00339 transferFunctionJacobian_(StateMemberYaw, StateMemberRoll) = dF8dr;
00340 transferFunctionJacobian_(StateMemberYaw, StateMemberPitch) = dF8dp;
00341
00342 FB_DEBUG("Transfer function is:\n" << transferFunction_ <<
00343 "\nTransfer function Jacobian is:\n" << transferFunctionJacobian_ <<
00344 "\nProcess noise covariance is:\n" << processNoiseCovariance_ <<
00345 "\nCurrent state is:\n" << state_ << "\n");
00346
00347
00348 state_ = transferFunction_ * state_;
00349
00350
00351 wrapStateAngles();
00352
00353 FB_DEBUG("Predicted state is:\n" << state_ <<
00354 "\nCurrent estimate error covariance is:\n" << estimateErrorCovariance_ << "\n");
00355
00356
00357 estimateErrorCovariance_ = (transferFunctionJacobian_ * estimateErrorCovariance_ * transferFunctionJacobian_.transpose());
00358 estimateErrorCovariance_.noalias() += (processNoiseCovariance_ * delta);
00359
00360 FB_DEBUG("Predicted estimate error covariance is:\n" << estimateErrorCovariance_ <<
00361 "\n\n--------------------- /Ekf::predict ----------------------\n");
00362 }
00363
00364 }