$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 /* Author: Wim Meeussen */ 00035 00036 #ifndef __ODOM_ESTIMATION__ 00037 #define __ODOM_ESTIMATION__ 00038 00039 // bayesian filtering 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 // TF 00049 #include <tf/tf.h> 00050 00051 // msgs 00052 #include <geometry_msgs/PoseWithCovarianceStamped.h> 00053 00054 // log files 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 // decompose Transform into x,y,z,Rx,Ry,Rz 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 // pdf / model / filter 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 // vars 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 // diagnostics 00155 double diagnostics_odom_rot_rel_, diagnostics_imu_rot_rel_; 00156 00157 // tf transformer 00158 tf::Transformer transformer_; 00159 00160 }; // class 00161 00162 }; // namespace 00163 00164 #endif