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 EKF_RTT_HPP_
00044 #define EKF_RTT_HPP_
00045 #include <labust/navigation/KFCore.hpp>
00046 #include <labust/navigation/RelativeTrackingModel.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 <std_msgs/Bool.h>
00057 #include <auv_msgs/NavSts.h>
00058 #include <underwater_msgs/USBLFix.h>
00059 
00060 namespace labust
00061 {
00062         namespace navigation
00063         {
00069                 class Estimator3D
00070                 {
00071                         enum{X=0,Y,Z,K,M,N, DoF};
00072                         typedef labust::navigation::KFCore<labust::navigation::RelativeTrackingModel> KFNav;
00073                 public:
00077                         Estimator3D();
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 onStateHat(const auv_msgs::NavSts::ConstPtr& data);
00103                         void onCurrentsHat(const  geometry_msgs::TwistStamped::ConstPtr& data);
00107                         void onTargetTau(const auv_msgs::BodyForceReq::ConstPtr& tau);
00111                         void onTargetDepth(const std_msgs::Float32::ConstPtr& data);
00115                         void onTargetHeading(const std_msgs::Float32::ConstPtr& data);
00119                         void onUSBLfix(const underwater_msgs::USBLFix::ConstPtr& data);
00123                         
00127                         
00131                         void processMeasurements();
00135                         void publishState();
00139                         KFNav nav;
00143                         KFNav::vector inputVec;
00147                         KFNav::vector measurements, newMeas;
00151                         labust::math::unwrap unwrap;
00155                         ros::Publisher pubStateMeas, pubStateHat;
00159                         ros::Subscriber subStateHat, subCurrentsHat, subTargetTau, subTargetDepth, subTargetHeading, subUSBLfix, modelUpdate;
00163                         tf2_ros::TransformBroadcaster broadcaster;
00167                         double alt, xc, yc, u, v;
00171                         KFNav::ModelParams params[DoF];
00172                 };
00173         }
00174 }
00175 
00176 #endif