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 #ifndef __ODOM_ESTIMATION__
00037 #define __ODOM_ESTIMATION__
00038
00039
00040 #include <filter/extendedkalmanfilter.h>
00041 #include <wrappers/matrix/matrix_wrapper.h>
00042 #include <model/linearanalyticsystemmodel_gaussianuncertainty.h>
00043 #include <model/linearanalyticmeasurementmodel_gaussianuncertainty.h>
00044 #include <pdf/analyticconditionalgaussian.h>
00045 #include <pdf/linearanalyticconditionalgaussian.h>
00046 #include "nonlinearanalyticconditionalgaussianodo.h"
00047
00048
00049 #include <tf/tf.h>
00050
00051
00052 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00053
00054
00055 #include <fstream>
00056
00057 namespace estimation
00058 {
00059
00060 class OdomEstimation
00061 {
00062 public:
00064 OdomEstimation();
00065
00067 virtual ~OdomEstimation();
00068
00077 bool update(bool odom_active, bool imu_active, bool vo_active, const ros::Time& filter_time, bool& diagnostics_res);
00078
00083 void initialize(const tf::Transform& prior, const ros::Time& time);
00084
00088 bool isInitialized() {return filter_initialized_;};
00089
00093 void getEstimate(MatrixWrapper::ColumnVector& estimate);
00094
00099 void getEstimate(ros::Time time, tf::Transform& estiamte);
00100
00105 void getEstimate(ros::Time time, tf::StampedTransform& estiamte);
00106
00110 void getEstimate(geometry_msgs::PoseWithCovarianceStamped& estimate);
00111
00115 void addMeasurement(const tf::StampedTransform& meas);
00116
00121 void addMeasurement(const tf::StampedTransform& meas, const MatrixWrapper::SymmetricMatrix& covar);
00122
00123 private:
00125 void angleOverflowCorrect(double& a, double ref);
00126
00127
00128 void decomposeTransform(const tf::StampedTransform& trans,
00129 double& x, double& y, double&z, double&Rx, double& Ry, double& Rz);
00130 void decomposeTransform(const tf::Transform& trans,
00131 double& x, double& y, double&z, double&Rx, double& Ry, double& Rz);
00132
00133
00134
00135 BFL::AnalyticSystemModelGaussianUncertainty* sys_model_;
00136 BFL::NonLinearAnalyticConditionalGaussianOdo* sys_pdf_;
00137 BFL::LinearAnalyticConditionalGaussian* odom_meas_pdf_;
00138 BFL::LinearAnalyticMeasurementModelGaussianUncertainty* odom_meas_model_;
00139 BFL::LinearAnalyticConditionalGaussian* imu_meas_pdf_;
00140 BFL::LinearAnalyticMeasurementModelGaussianUncertainty* imu_meas_model_;
00141 BFL::LinearAnalyticConditionalGaussian* vo_meas_pdf_;
00142 BFL::LinearAnalyticMeasurementModelGaussianUncertainty* vo_meas_model_;
00143 BFL::Gaussian* prior_;
00144 BFL::ExtendedKalmanFilter* filter_;
00145 MatrixWrapper::SymmetricMatrix odom_covariance_, imu_covariance_, vo_covariance_;
00146
00147
00148 MatrixWrapper::ColumnVector vel_desi_, filter_estimate_old_vec_;
00149 tf::Transform filter_estimate_old_;
00150 tf::StampedTransform odom_meas_, odom_meas_old_, imu_meas_, imu_meas_old_, vo_meas_, vo_meas_old_;
00151 ros::Time filter_time_old_;
00152 bool filter_initialized_, odom_initialized_, imu_initialized_, vo_initialized_;
00153
00154
00155 double diagnostics_odom_rot_rel_, diagnostics_imu_rot_rel_;
00156
00157
00158 tf::Transformer transformer_;
00159
00160 };
00161
00162 };
00163
00164 #endif