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 #ifndef EKF3D_HPP_
00044 #define EKF3D_HPP_
00045 #include <labust/navigation/KFCore.hpp>
00046 #include <labust/navigation/LDTravModelExtended.hpp>
00047 #include <labust/navigation/SensorHandlers.hpp>
00048 #include <labust/math/NumberManipulation.hpp>
00049 #include <navcon_msgs/ModelParamsUpdate.h>
00050 
00051 #include <tf2_ros/transform_broadcaster.h>
00052 #include <std_msgs/Float32.h>
00053 #include <std_msgs/Bool.h>
00054 #include <auv_msgs/BodyForceReq.h>
00055 
00056 #include <auv_msgs/NED.h> 
00057 #include <std_msgs/Bool.h>
00058 
00059 namespace labust
00060 {
00061         namespace navigation
00062         {
00068                 class Estimator3D
00069                 {
00070                         enum{X=0,Y,Z,K,M,N, DoF};
00071                         typedef labust::navigation::KFCore<labust::navigation::LDTravModel> KFNav;
00072                 public:
00076                         Estimator3D();
00077 
00081                         void onInit();
00085                         void start();
00086 
00087                 private:
00091                         void configureNav(KFNav& nav, ros::NodeHandle& nh);
00095                         void onModelUpdate(const navcon_msgs::ModelParamsUpdate::ConstPtr& update);
00099                         void onTau(const auv_msgs::BodyForceReq::ConstPtr& tau);
00103                         void onDepth(const std_msgs::Float32::ConstPtr& data);
00107                         void onAltitude(const std_msgs::Float32::ConstPtr& data);
00111                         void processMeasurements();
00115                         void publishState();
00119                         void onReset(const std_msgs::Bool::ConstPtr& reset);
00123                         void onUseGyro(const std_msgs::Bool::ConstPtr& use_gyro);
00124 
00128                         KFNav nav;
00132                         KFNav::vector tauIn;
00136                         KFNav::vector measurements, newMeas;
00140                         labust::math::unwrap unwrap;
00144                         ros::Publisher stateMeas, stateHat, currentsHat, buoyancyHat, unsafe_dvl;
00146                         ros::Publisher turns_pub;
00150                         ros::Subscriber tauAch, depth, altitude, modelUpdate, resetTopic, useGyro, sub, subKFmode;
00154                         GPSHandler gps;
00158                         ImuHandler imu;
00162                         DvlHandler dvl;
00164                         double max_dvl;
00166                         double min_altitude;
00168                         ros::Time dvl_time;
00170                         double dvl_timeout;
00174                         tf2_ros::TransformBroadcaster broadcaster;
00178                         double alt;
00182                         KFNav::ModelParams params[DoF];
00186                         bool useYawRate;
00190                         int dvl_model;
00194                         double compassVariance, gyroVariance;
00196                         boost::mutex meas_mux;
00197 
00201                         void deltaPosCallback(const auv_msgs::NED::ConstPtr& msg);
00202 
00203                         void KFmodeCallback(const std_msgs::Bool::ConstPtr& msg);
00204 
00208                         bool quadMeasAvailable, KFmode, KFmodePast, absoluteEKF;
00209 
00210                         float deltaXpos, deltaYpos;
00211 
00212                         KFNav::matrix Pstart, Rstart;
00213 
00214                 };
00215         }
00216 }
00217 
00218 #endif