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
00034
00035
00036
00037 #include <robot_pose_ekf/odom_estimation.h>
00038
00039 using namespace MatrixWrapper;
00040 using namespace BFL;
00041 using namespace tf;
00042 using namespace std;
00043 using namespace ros;
00044
00045
00046 namespace estimation
00047 {
00048
00049 OdomEstimation::OdomEstimation():
00050 prior_(NULL),
00051 filter_(NULL),
00052 filter_initialized_(false),
00053 odom_initialized_(false),
00054 imu_initialized_(false),
00055 vo_initialized_(false),
00056 gps_initialized_(false)
00057 {
00058
00059 ColumnVector sysNoise_Mu(6); sysNoise_Mu = 0;
00060 SymmetricMatrix sysNoise_Cov(6); sysNoise_Cov = 0;
00061 for (unsigned int i=1; i<=6; i++) sysNoise_Cov(i,i) = pow(1000.0,2);
00062 Gaussian system_Uncertainty(sysNoise_Mu, sysNoise_Cov);
00063 sys_pdf_ = new NonLinearAnalyticConditionalGaussianOdo(system_Uncertainty);
00064 sys_model_ = new AnalyticSystemModelGaussianUncertainty(sys_pdf_);
00065
00066
00067 ColumnVector measNoiseOdom_Mu(6); measNoiseOdom_Mu = 0;
00068 SymmetricMatrix measNoiseOdom_Cov(6); measNoiseOdom_Cov = 0;
00069 for (unsigned int i=1; i<=6; i++) measNoiseOdom_Cov(i,i) = 1;
00070 Gaussian measurement_Uncertainty_Odom(measNoiseOdom_Mu, measNoiseOdom_Cov);
00071 Matrix Hodom(6,6); Hodom = 0;
00072 Hodom(1,1) = 1; Hodom(2,2) = 1; Hodom(6,6) = 1;
00073 odom_meas_pdf_ = new LinearAnalyticConditionalGaussian(Hodom, measurement_Uncertainty_Odom);
00074 odom_meas_model_ = new LinearAnalyticMeasurementModelGaussianUncertainty(odom_meas_pdf_);
00075
00076
00077 ColumnVector measNoiseImu_Mu(3); measNoiseImu_Mu = 0;
00078 SymmetricMatrix measNoiseImu_Cov(3); measNoiseImu_Cov = 0;
00079 for (unsigned int i=1; i<=3; i++) measNoiseImu_Cov(i,i) = 1;
00080 Gaussian measurement_Uncertainty_Imu(measNoiseImu_Mu, measNoiseImu_Cov);
00081 Matrix Himu(3,6); Himu = 0;
00082 Himu(1,4) = 1; Himu(2,5) = 1; Himu(3,6) = 1;
00083 imu_meas_pdf_ = new LinearAnalyticConditionalGaussian(Himu, measurement_Uncertainty_Imu);
00084 imu_meas_model_ = new LinearAnalyticMeasurementModelGaussianUncertainty(imu_meas_pdf_);
00085
00086
00087 ColumnVector measNoiseVo_Mu(6); measNoiseVo_Mu = 0;
00088 SymmetricMatrix measNoiseVo_Cov(6); measNoiseVo_Cov = 0;
00089 for (unsigned int i=1; i<=6; i++) measNoiseVo_Cov(i,i) = 1;
00090 Gaussian measurement_Uncertainty_Vo(measNoiseVo_Mu, measNoiseVo_Cov);
00091 Matrix Hvo(6,6); Hvo = 0;
00092 Hvo(1,1) = 1; Hvo(2,2) = 1; Hvo(3,3) = 1; Hvo(4,4) = 1; Hvo(5,5) = 1; Hvo(6,6) = 1;
00093 vo_meas_pdf_ = new LinearAnalyticConditionalGaussian(Hvo, measurement_Uncertainty_Vo);
00094 vo_meas_model_ = new LinearAnalyticMeasurementModelGaussianUncertainty(vo_meas_pdf_);
00095
00096
00097
00098
00099 ColumnVector measNoiseGps_Mu(3); measNoiseGps_Mu = 0;
00100 SymmetricMatrix measNoiseGps_Cov(3); measNoiseGps_Cov = 0;
00101 for (unsigned int i=1; i<=3; i++) measNoiseGps_Cov(i,i) = 1;
00102 Gaussian measurement_Uncertainty_GPS(measNoiseGps_Mu, measNoiseGps_Cov);
00103 Matrix Hgps(3,6); Hgps = 0;
00104 Hgps(1,1) = 1; Hgps(2,2) = 1; Hgps(3,3) = 1;
00105 gps_meas_pdf_ = new LinearAnalyticConditionalGaussian(Hgps, measurement_Uncertainty_GPS);
00106 gps_meas_model_ = new LinearAnalyticMeasurementModelGaussianUncertainty(gps_meas_pdf_);
00107 };
00108
00109
00110
00111
00112 OdomEstimation::~OdomEstimation(){
00113 if (filter_) delete filter_;
00114 if (prior_) delete prior_;
00115 delete odom_meas_model_;
00116 delete odom_meas_pdf_;
00117 delete imu_meas_model_;
00118 delete imu_meas_pdf_;
00119 delete vo_meas_model_;
00120 delete vo_meas_pdf_;
00121 delete gps_meas_model_;
00122 delete gps_meas_pdf_;
00123 delete sys_pdf_;
00124 delete sys_model_;
00125 };
00126
00127
00128
00129 void OdomEstimation::initialize(const Transform& prior, const Time& time)
00130 {
00131
00132 ColumnVector prior_Mu(6);
00133 decomposeTransform(prior, prior_Mu(1), prior_Mu(2), prior_Mu(3), prior_Mu(4), prior_Mu(5), prior_Mu(6));
00134 SymmetricMatrix prior_Cov(6);
00135 for (unsigned int i=1; i<=6; i++) {
00136 for (unsigned int j=1; j<=6; j++){
00137 if (i==j) prior_Cov(i,j) = pow(0.001,2);
00138 else prior_Cov(i,j) = 0;
00139 }
00140 }
00141 prior_ = new Gaussian(prior_Mu,prior_Cov);
00142 filter_ = new ExtendedKalmanFilter(prior_);
00143
00144
00145 addMeasurement(StampedTransform(prior, time, "odom_combined", "base_footprint"));
00146 filter_estimate_old_vec_ = prior_Mu;
00147 filter_estimate_old_ = prior;
00148 filter_time_old_ = time;
00149
00150
00151 filter_initialized_ = true;
00152 }
00153
00154
00155
00156
00157
00158
00159 bool OdomEstimation::update(bool odom_active, bool imu_active, bool gps_active, bool vo_active, const Time& filter_time, bool& diagnostics_res)
00160 {
00161
00162 if (!filter_initialized_){
00163 ROS_INFO("Cannot update filter when filter was not initialized first.");
00164 return false;
00165 }
00166
00167
00168 double dt = (filter_time - filter_time_old_).toSec();
00169 if (dt == 0) return false;
00170 if (dt < 0){
00171 ROS_INFO("Will not update robot pose with time %f sec in the past.", dt);
00172 return false;
00173 }
00174 ROS_DEBUG("Update filter at time %f with dt %f", filter_time.toSec(), dt);
00175
00176
00177
00178
00179
00180 ColumnVector vel_desi(2); vel_desi = 0;
00181 filter_->Update(sys_model_, vel_desi);
00182
00183
00184
00185
00186 ROS_DEBUG("Process odom meas");
00187 if (odom_active){
00188 if (!transformer_.canTransform("base_footprint","wheelodom", filter_time)){
00189 ROS_ERROR("filter time older than odom message buffer");
00190 return false;
00191 }
00192 transformer_.lookupTransform("wheelodom", "base_footprint", filter_time, odom_meas_);
00193 if (odom_initialized_){
00194
00195 Transform odom_rel_frame = Transform(tf::createQuaternionFromYaw(filter_estimate_old_vec_(6)),
00196 filter_estimate_old_.getOrigin()) * odom_meas_old_.inverse() * odom_meas_;
00197 ColumnVector odom_rel(6);
00198 decomposeTransform(odom_rel_frame, odom_rel(1), odom_rel(2), odom_rel(3), odom_rel(4), odom_rel(5), odom_rel(6));
00199 angleOverflowCorrect(odom_rel(6), filter_estimate_old_vec_(6));
00200
00201 odom_meas_pdf_->AdditiveNoiseSigmaSet(odom_covariance_ * pow(dt,2));
00202
00203 ROS_DEBUG("Update filter with odom measurement %f %f %f %f %f %f",
00204 odom_rel(1), odom_rel(2), odom_rel(3), odom_rel(4), odom_rel(5), odom_rel(6));
00205 filter_->Update(odom_meas_model_, odom_rel);
00206 diagnostics_odom_rot_rel_ = odom_rel(6);
00207 }
00208 else{
00209 odom_initialized_ = true;
00210 diagnostics_odom_rot_rel_ = 0;
00211 }
00212 odom_meas_old_ = odom_meas_;
00213 }
00214
00215 else odom_initialized_ = false;
00216
00217
00218
00219
00220 if (imu_active){
00221 if (!transformer_.canTransform("base_footprint","imu", filter_time)){
00222 ROS_ERROR("filter time older than imu message buffer");
00223 return false;
00224 }
00225 transformer_.lookupTransform("imu", "base_footprint", filter_time, imu_meas_);
00226 if (imu_initialized_){
00227
00228 Transform imu_rel_frame = filter_estimate_old_ * imu_meas_old_.inverse() * imu_meas_;
00229 ColumnVector imu_rel(3); double tmp;
00230 decomposeTransform(imu_rel_frame, tmp, tmp, tmp, tmp, tmp, imu_rel(3));
00231 decomposeTransform(imu_meas_, tmp, tmp, tmp, imu_rel(1), imu_rel(2), tmp);
00232 angleOverflowCorrect(imu_rel(3), filter_estimate_old_vec_(6));
00233 diagnostics_imu_rot_rel_ = imu_rel(3);
00234
00235 imu_meas_pdf_->AdditiveNoiseSigmaSet(imu_covariance_ * pow(dt,2));
00236 filter_->Update(imu_meas_model_, imu_rel);
00237 }
00238 else{
00239 imu_initialized_ = true;
00240 diagnostics_imu_rot_rel_ = 0;
00241 }
00242 imu_meas_old_ = imu_meas_;
00243 }
00244
00245 else imu_initialized_ = false;
00246
00247
00248
00249
00250
00251 if (vo_active){
00252 if (!transformer_.canTransform("base_footprint","vo", filter_time)){
00253 ROS_ERROR("filter time older than vo message buffer");
00254 return false;
00255 }
00256 transformer_.lookupTransform("vo", "base_footprint", filter_time, vo_meas_);
00257 if (vo_initialized_){
00258
00259 Transform vo_rel_frame = filter_estimate_old_ * vo_meas_old_.inverse() * vo_meas_;
00260 ColumnVector vo_rel(6);
00261 decomposeTransform(vo_rel_frame, vo_rel(1), vo_rel(2), vo_rel(3), vo_rel(4), vo_rel(5), vo_rel(6));
00262 angleOverflowCorrect(vo_rel(6), filter_estimate_old_vec_(6));
00263
00264 vo_meas_pdf_->AdditiveNoiseSigmaSet(vo_covariance_ * pow(dt,2));
00265 filter_->Update(vo_meas_model_, vo_rel);
00266 }
00267 else vo_initialized_ = true;
00268 vo_meas_old_ = vo_meas_;
00269 }
00270
00271 else vo_initialized_ = false;
00272
00273
00274
00275
00276
00277 if (gps_active){
00278 if (!transformer_.canTransform("base_footprint","gps", filter_time)){
00279 ROS_ERROR("filter time older than gps message buffer");
00280 return false;
00281 }
00282 transformer_.lookupTransform("gps", "base_footprint", filter_time, gps_meas_);
00283 if (gps_initialized_){
00284 gps_meas_pdf_->AdditiveNoiseSigmaSet(gps_covariance_ * pow(dt,2));
00285 ColumnVector gps_vec(3);
00286 double tmp;
00287
00288 decomposeTransform(gps_meas_, gps_vec(1), gps_vec(2), gps_vec(3), tmp, tmp, tmp);
00289 filter_->Update(gps_meas_model_, gps_vec);
00290 }
00291 else {
00292 gps_initialized_ = true;
00293 gps_meas_old_ = gps_meas_;
00294 }
00295 }
00296
00297 else gps_initialized_ = false;
00298
00299
00300
00301
00302 filter_estimate_old_vec_ = filter_->PostGet()->ExpectedValueGet();
00303 tf::Quaternion q;
00304 q.setRPY(filter_estimate_old_vec_(4), filter_estimate_old_vec_(5), filter_estimate_old_vec_(6));
00305 filter_estimate_old_ = Transform(q,
00306 Vector3(filter_estimate_old_vec_(1), filter_estimate_old_vec_(2), filter_estimate_old_vec_(3)));
00307 filter_time_old_ = filter_time;
00308 addMeasurement(StampedTransform(filter_estimate_old_, filter_time, "odom_combined", "base_footprint"));
00309
00310
00311 diagnostics_res = true;
00312 if (odom_active && imu_active){
00313 double diagnostics = fabs(diagnostics_odom_rot_rel_ - diagnostics_imu_rot_rel_)/dt;
00314 if (diagnostics > 0.3 && dt > 0.01){
00315 diagnostics_res = false;
00316 }
00317 }
00318
00319 return true;
00320 };
00321
00322 void OdomEstimation::addMeasurement(const StampedTransform& meas)
00323 {
00324 ROS_DEBUG("AddMeasurement from %s to %s: (%f, %f, %f) (%f, %f, %f, %f)",
00325 meas.frame_id_.c_str(), meas.child_frame_id_.c_str(),
00326 meas.getOrigin().x(), meas.getOrigin().y(), meas.getOrigin().z(),
00327 meas.getRotation().x(), meas.getRotation().y(),
00328 meas.getRotation().z(), meas.getRotation().w());
00329 transformer_.setTransform( meas );
00330 }
00331
00332 void OdomEstimation::addMeasurement(const StampedTransform& meas, const MatrixWrapper::SymmetricMatrix& covar)
00333 {
00334
00335 for (unsigned int i=0; i<covar.rows(); i++){
00336 if (covar(i+1,i+1) == 0){
00337 ROS_ERROR("Covariance specified for measurement on topic %s is zero", meas.child_frame_id_.c_str());
00338 return;
00339 }
00340 }
00341
00342 addMeasurement(meas);
00343 if (meas.child_frame_id_ == "wheelodom") odom_covariance_ = covar;
00344 else if (meas.child_frame_id_ == "imu") imu_covariance_ = covar;
00345 else if (meas.child_frame_id_ == "vo") vo_covariance_ = covar;
00346 else if (meas.child_frame_id_ == "gps") gps_covariance_ = covar;
00347 else ROS_ERROR("Adding a measurement for an unknown sensor %s", meas.child_frame_id_.c_str());
00348 };
00349
00350
00351
00352 void OdomEstimation::getEstimate(ColumnVector& estimate)
00353 {
00354 estimate = filter_estimate_old_vec_;
00355 };
00356
00357
00358 void OdomEstimation::getEstimate(Time time, Transform& estimate)
00359 {
00360 StampedTransform tmp;
00361 if (!transformer_.canTransform("base_footprint","odom_combined", time)){
00362 ROS_ERROR("Cannot get transform at time %f", time.toSec());
00363 return;
00364 }
00365 transformer_.lookupTransform("odom_combined", "base_footprint", time, tmp);
00366 estimate = tmp;
00367 };
00368
00369
00370 void OdomEstimation::getEstimate(Time time, StampedTransform& estimate)
00371 {
00372 if (!transformer_.canTransform("odom_combined", "base_footprint", time)){
00373 ROS_ERROR("Cannot get transform at time %f", time.toSec());
00374 return;
00375 }
00376 transformer_.lookupTransform("odom_combined", "base_footprint", time, estimate);
00377 };
00378
00379
00380 void OdomEstimation::getEstimate(geometry_msgs::PoseWithCovarianceStamped& estimate)
00381 {
00382
00383 StampedTransform tmp;
00384 if (!transformer_.canTransform("odom_combined", "base_footprint", ros::Time())){
00385 ROS_ERROR("Cannot get transform at time %f", 0.0);
00386 return;
00387 }
00388 transformer_.lookupTransform("odom_combined", "base_footprint", ros::Time(), tmp);
00389 poseTFToMsg(tmp, estimate.pose.pose);
00390
00391
00392 estimate.header.stamp = tmp.stamp_;
00393 estimate.header.frame_id = "odom";
00394
00395
00396 SymmetricMatrix covar = filter_->PostGet()->CovarianceGet();
00397 for (unsigned int i=0; i<6; i++)
00398 for (unsigned int j=0; j<6; j++)
00399 estimate.pose.covariance[6*i+j] = covar(i+1,j+1);
00400 };
00401
00402
00403 void OdomEstimation::angleOverflowCorrect(double& a, double ref)
00404 {
00405 while ((a-ref) > M_PI) a -= 2*M_PI;
00406 while ((a-ref) < -M_PI) a += 2*M_PI;
00407 };
00408
00409
00410 void OdomEstimation::decomposeTransform(const StampedTransform& trans,
00411 double& x, double& y, double&z, double&Rx, double& Ry, double& Rz){
00412 x = trans.getOrigin().x();
00413 y = trans.getOrigin().y();
00414 z = trans.getOrigin().z();
00415 trans.getBasis().getEulerYPR(Rz, Ry, Rx);
00416 };
00417
00418
00419 void OdomEstimation::decomposeTransform(const Transform& trans,
00420 double& x, double& y, double&z, double&Rx, double& Ry, double& Rz){
00421 x = trans.getOrigin().x();
00422 y = trans.getOrigin().y();
00423 z = trans.getOrigin().z();
00424 trans.getBasis().getEulerYPR(Rz, Ry, Rx);
00425 };
00426
00427 };