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 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 
00042 
00043 
00044 #ifndef EKF_3D_USBL_HPP_
00045 #define EKF_3D_USBL_HPP_
00046 #include <labust/navigation/KFCore.hpp>
00047 #include <labust/navigation/EKF_3D_USBLModel.hpp>
00048 #include <labust/navigation/SensorHandlers.hpp>
00049 #include <labust/math/NumberManipulation.hpp>
00050 #include <navcon_msgs/ModelParamsUpdate.h>
00051 #include <labust/tools/OutlierRejection.hpp>
00052 
00053 
00054 #include <tf2_ros/transform_broadcaster.h>
00055 #include <std_msgs/Float32.h>
00056 #include <std_msgs/Bool.h>
00057 #include <auv_msgs/BodyForceReq.h>
00058 #include <underwater_msgs/USBLFix.h>
00059 
00060 #include <auv_msgs/NED.h>
00061 #include <std_msgs/Bool.h>
00062 
00063 #include <stack>
00064 #include <deque>
00065 
00066 
00067 namespace labust
00068 {
00069         namespace navigation
00070         {
00076                 class Estimator3D
00077                 {
00078                         enum{X=0,Y,Z,K,M,N, DoF};
00079                         typedef labust::navigation::KFCore<labust::navigation::EKF_3D_USBLModel> KFNav;
00080                 public:
00084                         Estimator3D();
00085 
00089                         void onInit();
00093                         void start();
00094 
00095                         struct FilterState{
00096 
00097                                 FilterState(){
00098 
00099                                 }
00100 
00101                                 ~FilterState(){
00102 
00103                                 }
00104 
00105                                 KFNav::vector input;
00106                                 KFNav::vector meas;
00107                                 KFNav::vector newMeas;
00108                                 KFNav::vector state;
00109                                 KFNav::matrix Pcov;
00110                                 KFNav::matrix Rcov;
00111 
00112                         };
00113 
00114                 private:
00118                         void configureNav(KFNav& nav, ros::NodeHandle& nh);
00122                         void onModelUpdate(const navcon_msgs::ModelParamsUpdate::ConstPtr& update);
00126                         void onTau(const auv_msgs::BodyForceReq::ConstPtr& tau);
00130                         void onDepth(const std_msgs::Float32::ConstPtr& data);
00134                         void onAltitude(const std_msgs::Float32::ConstPtr& data);
00138                         void onUSBLfix(const underwater_msgs::USBLFix::ConstPtr& data);
00142                         void processMeasurements();
00146                         void publishState();
00150                         void onReset(const std_msgs::Bool::ConstPtr& reset);
00154                         void onUseGyro(const std_msgs::Bool::ConstPtr& use_gyro);
00158                         int calculateDelaySteps(double measTime, double arrivalTime);
00162                         KFNav nav;
00166                         KFNav::vector tauIn;
00170                         KFNav::vector measurements, newMeas, measDelay;
00174                         labust::math::unwrap unwrap;
00178                         ros::Publisher stateMeas, stateHat, currentsHat, buoyancyHat, pubRange, pubRangeFiltered, pubwk;
00182                         ros::Subscriber tauAch, depth, altitude, modelUpdate, resetTopic, useGyro, sub, subKFmode, subUSBL;
00186                         GPSHandler gps;
00190                         ImuHandler imu;
00194                         DvlHandler dvl;
00198                         tf2_ros::TransformBroadcaster broadcaster;
00202                         double alt;
00206                         KFNav::ModelParams params[DoF];
00210                         bool useYawRate;
00214                         int dvl_model;
00218                         double compassVariance, gyroVariance;
00219 
00223                         double currentTime;
00224                         double delayTime;
00228                         double delay_time;
00232                         bool enableDelay, enableRange, enableBearing, enableElevation;
00233 
00237                         void deltaPosCallback(const auv_msgs::NED::ConstPtr& msg);
00238 
00239                         void KFmodeCallback(const std_msgs::Bool::ConstPtr& msg);
00240 
00244                         bool quadMeasAvailable, KFmode, KFmodePast, absoluteEKF;
00245 
00246                         float deltaXpos, deltaYpos;
00247 
00248                         KFNav::matrix Pstart, Rstart;
00249 
00250                         std::deque<FilterState> pastStates;
00251 
00252                         labust::tools::OutlierRejection OR;
00253 
00254                 };
00255         }
00256 }
00257 
00258 #endif