Go to the documentation of this file.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/filter_common.h>
00034 #include <robot_localization/ekf.h>
00035
00036 #include <XmlRpcException.h>
00037
00038 #include <sstream>
00039 #include <iomanip>
00040 #include <limits>
00041
00042 namespace RobotLocalization
00043 {
00044 Ekf::Ekf() :
00045 FilterBase()
00046 {
00047 }
00048
00049 Ekf::~Ekf()
00050 {
00051 }
00052
00053 void Ekf::correct(const Measurement &measurement)
00054 {
00055 if (getDebug())
00056 {
00057 *debugStream_ << "---------------------- Ekf::correct ----------------------\n";
00058 *debugStream_ << "State is:\n";
00059 *debugStream_ << state_ << "\n";
00060 *debugStream_ << "Measurement is:\n";
00061 *debugStream_ << measurement.measurement_ << "\n";
00062 *debugStream_ << "Measurement covariance is:\n";
00063 *debugStream_ << measurement.covariance_ << "\n";
00064 }
00065
00066
00067
00068
00069
00070 std::vector<size_t> updateIndices;
00071 for (size_t i = 0; i < measurement.updateVector_.size(); ++i)
00072 {
00073 if (measurement.updateVector_[i])
00074 {
00075
00076 if (std::isnan(measurement.measurement_(i)))
00077 {
00078 if (getDebug())
00079 {
00080 *debugStream_ << "Value at index " << i << " was nan. Excluding from update.\n";
00081 }
00082 }
00083 else if (std::isinf(measurement.measurement_(i)))
00084 {
00085 if (getDebug())
00086 {
00087 *debugStream_ << "Value at index " << i << " was inf. Excluding from update.\n";
00088 }
00089 }
00090 else
00091 {
00092 updateIndices.push_back(i);
00093 }
00094 }
00095 }
00096
00097 if (getDebug())
00098 {
00099 *debugStream_ << "Update indices are:\n";
00100 *debugStream_ << updateIndices << "\n";
00101 }
00102
00103 size_t updateSize = updateIndices.size();
00104
00105
00106 Eigen::VectorXd stateSubset(updateSize);
00107 Eigen::VectorXd measurementSubset(updateSize);
00108 Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize);
00109 Eigen::MatrixXd stateToMeasurementSubset(updateSize, state_.rows());
00110 Eigen::MatrixXd kalmanGainSubset(state_.rows(), updateSize);
00111 Eigen::VectorXd innovationSubset(updateSize);
00112
00113 stateSubset.setZero();
00114 measurementSubset.setZero();
00115 measurementCovarianceSubset.setZero();
00116 stateToMeasurementSubset.setZero();
00117 kalmanGainSubset.setZero();
00118 innovationSubset.setZero();
00119
00120
00121 for (size_t i = 0; i < updateSize; ++i)
00122 {
00123 measurementSubset(i) = measurement.measurement_(updateIndices[i]);
00124 stateSubset(i) = state_(updateIndices[i]);
00125
00126 for (size_t j = 0; j < updateSize; ++j)
00127 {
00128 measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]);
00129 }
00130
00131
00132
00133
00134 if (measurementCovarianceSubset(i, i) < 0)
00135 {
00136 if (getDebug())
00137 {
00138 *debugStream_ << "WARNING: Negative covariance for index " << i << " of measurement (value is" << measurementCovarianceSubset(i, i)
00139 << "). Using absolute value...\n";
00140 }
00141
00142 measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i));
00143 }
00144
00145
00146
00147
00148
00149
00150
00151 if (measurementCovarianceSubset(i, i) < 1e-6)
00152 {
00153 measurementCovarianceSubset(i, i) = 1e-6;
00154
00155 if (getDebug())
00156 {
00157 *debugStream_ << "WARNING: measurement had very small error covariance for index " << i << ". Adding some noise to maintain filter stability.\n";
00158 }
00159 }
00160 }
00161
00162
00163
00164 for (size_t i = 0; i < updateSize; ++i)
00165 {
00166 stateToMeasurementSubset(i, updateIndices[i]) = 1;
00167 }
00168
00169 if (getDebug())
00170 {
00171 *debugStream_ << "Current state subset is:\n";
00172 *debugStream_ << stateSubset << "\n";
00173 *debugStream_ << "Measurement subset is:\n";
00174 *debugStream_ << measurementSubset << "\n";
00175 *debugStream_ << "Measurement covariance subset is:\n";
00176 *debugStream_ << measurementCovarianceSubset << "\n";
00177 *debugStream_ << "State-to-measurement subset is:\n";
00178 *debugStream_ << stateToMeasurementSubset << "\n";
00179 }
00180
00181
00182 kalmanGainSubset = estimateErrorCovariance_ * stateToMeasurementSubset.transpose()
00183 * (stateToMeasurementSubset * estimateErrorCovariance_ * stateToMeasurementSubset.transpose() + measurementCovarianceSubset).inverse();
00184
00185
00186 innovationSubset = (measurementSubset - stateSubset);
00187
00188
00189 for (size_t i = 0; i < updateSize; ++i)
00190 {
00191 if (updateIndices[i] == StateMemberRoll || updateIndices[i] == StateMemberPitch || updateIndices[i] == StateMemberYaw)
00192 {
00193 if (innovationSubset(i) < -pi_)
00194 {
00195 innovationSubset(i) += tau_;
00196 }
00197 else if (innovationSubset(i) > pi_)
00198 {
00199 innovationSubset(i) -= tau_;
00200 }
00201 }
00202 }
00203
00204 state_ = state_ + kalmanGainSubset * innovationSubset;
00205
00206
00207 Eigen::MatrixXd gainResidual = identity_ - kalmanGainSubset * stateToMeasurementSubset;
00208 estimateErrorCovariance_ = gainResidual * estimateErrorCovariance_ * gainResidual.transpose() +
00209 kalmanGainSubset * measurementCovarianceSubset * kalmanGainSubset.transpose();
00210
00211
00212 wrapStateAngles();
00213
00214 if (getDebug())
00215 {
00216 *debugStream_ << "Kalman gain subset is:\n";
00217 *debugStream_ << kalmanGainSubset << "\n";
00218 *debugStream_ << "Innovation:\n";
00219 *debugStream_ << innovationSubset << "\n\n";
00220 *debugStream_ << "Corrected full state is:\n";
00221 *debugStream_ << state_ << "\n";
00222 *debugStream_ << "Corrected full estimate error covariance is:\n";
00223 *debugStream_ << estimateErrorCovariance_ << "\n";
00224 *debugStream_ << "\n---------------------- /Ekf::correct ----------------------\n";
00225 }
00226 }
00227
00228 void Ekf::predict(const double delta)
00229 {
00230 if (getDebug())
00231 {
00232 *debugStream_ << "---------------------- Ekf::predict ----------------------\n";
00233 *debugStream_ << "delta is " << delta << "\n";
00234 *debugStream_ << "state is " << state_ << "\n";
00235 }
00236
00237 double roll = state_(StateMemberRoll);
00238 double pitch = state_(StateMemberPitch);
00239 double yaw = state_(StateMemberYaw);
00240 double xVel = state_(StateMemberVx);
00241 double yVel = state_(StateMemberVy);
00242 double zVel = state_(StateMemberVz);
00243
00244
00245 double cr = cos(roll);
00246 double cp = cos(pitch);
00247 double cy = cos(yaw);
00248 double sr = sin(roll);
00249 double sp = sin(pitch);
00250 double sy = sin(yaw);
00251
00252
00253 transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta;
00254 transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta;
00255 transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta;
00256 transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta;
00257 transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta;
00258 transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta;
00259 transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta;
00260 transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta;
00261 transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta;
00262 transferFunction_(StateMemberRoll, StateMemberVroll) = delta;
00263 transferFunction_(StateMemberPitch, StateMemberVpitch) = delta;
00264 transferFunction_(StateMemberYaw, StateMemberVyaw) = delta;
00265
00266
00267
00268 double dF0dr = (cy * sp * cr + sy * sr) * delta * yVel + (-cy * sp * sr + sy * cr) * delta * zVel;
00269 double dF0dp = -cy * sp * delta * xVel + cy * cp * sr * delta * yVel + cy * cp * cr * delta * zVel;
00270 double dF0dy = -sy * cp * delta * xVel + (-sy * sp * sr - cy * cr) * delta * yVel + (-sy * sp * cr + cy * sr) * delta * zVel;
00271 double dF1dr = (sy * sp * cr - cy * sr) * delta * yVel + (-sy * sp * sr - cy * cr) * delta * zVel;
00272 double dF1dp = -sy * sp * delta * xVel + sy * cp * sr * delta * yVel + sy * cp * cr * delta * zVel;
00273 double dF1dy = cy * cp * delta * xVel + (cy * sp * sr - sy * cr) * delta * yVel + (cy * sp * cr + sy * sr) * delta * zVel;
00274 double dF2dr = cp * cr * delta * yVel - cp * sr * delta * zVel;
00275 double dF2dp = -cp * delta * xVel - sp * sr * delta * yVel - sp * cr * delta * zVel;
00276
00277
00278 transferFunctionJacobian_ = transferFunction_;
00279 transferFunctionJacobian_(StateMemberX, StateMemberRoll) = dF0dr;
00280 transferFunctionJacobian_(StateMemberX, StateMemberPitch) = dF0dp;
00281 transferFunctionJacobian_(StateMemberX, StateMemberYaw) = dF0dy;
00282 transferFunctionJacobian_(StateMemberY, StateMemberRoll) = dF1dr;
00283 transferFunctionJacobian_(StateMemberY, StateMemberPitch) = dF1dp;
00284 transferFunctionJacobian_(StateMemberY, StateMemberYaw) = dF1dy;
00285 transferFunctionJacobian_(StateMemberZ, StateMemberRoll) = dF2dr;
00286 transferFunctionJacobian_(StateMemberZ, StateMemberPitch) = dF2dp;
00287
00288 if (getDebug())
00289 {
00290 *debugStream_ << "Transfer function is:\n";
00291 *debugStream_ << transferFunction_ << "\n";
00292 *debugStream_ << "Transfer function Jacobian is:\n";
00293 *debugStream_ << transferFunctionJacobian_ << "\n";
00294 *debugStream_ << "Process noise covariance is " << "\n";
00295 *debugStream_ << processNoiseCovariance_ << "\n";
00296 *debugStream_ << "Current state is:\n";
00297 *debugStream_ << state_ << "\n";
00298 }
00299
00300
00301 state_ = transferFunction_ * state_;
00302
00303
00304 wrapStateAngles();
00305
00306 if (getDebug())
00307 {
00308 *debugStream_ << "Predicted state is:\n";
00309 *debugStream_ << state_ << "\n";
00310 *debugStream_ << "Current estimate error covariance is:\n";
00311 *debugStream_ << estimateErrorCovariance_ << "\n";
00312 }
00313
00314
00315 estimateErrorCovariance_ = (transferFunctionJacobian_ * estimateErrorCovariance_ * transferFunctionJacobian_.transpose())
00316 + (processNoiseCovariance_ * delta);
00317
00318 if (getDebug())
00319 {
00320 *debugStream_ << "Predicted estimate error covariance is:\n";
00321 *debugStream_ << estimateErrorCovariance_ << "\n";
00322 *debugStream_ << "\n--------------------- /Ekf::predict ----------------------\n";
00323 }
00324 }
00325
00326 }
00327
00328