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