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 #ifndef ESTIMATOR3D_HPP_
00035 #define ESTIMATOR3D_HPP_
00036 #include <labust/navigation/KFCore.hpp>
00037 #include <labust/navigation/LDTravModel.hpp>
00038 #include <labust/navigation/SensorHandlers.hpp>
00039 #include <labust/math/NumberManipulation.hpp>
00040 #include <navcon_msgs/ModelParamsUpdate.h>
00041
00042 #include <tf/transform_broadcaster.h>
00043 #include <tf/transform_listener.h>
00044 #include <std_msgs/Float32.h>
00045 #include <auv_msgs/BodyForceReq.h>
00046
00047 namespace labust
00048 {
00049 namespace navigation
00050 {
00056 class Estimator3D
00057 {
00058 enum{X=0,Y,Z,K,M,N, DoF};
00059 typedef labust::navigation::KFCore<labust::navigation::LDTravModel> KFNav;
00060 public:
00064 Estimator3D();
00065
00069 void onInit();
00073 void start();
00074
00075 private:
00079 void configureNav(KFNav& nav, ros::NodeHandle& nh);
00083 void onModelUpdate(const navcon_msgs::ModelParamsUpdate::ConstPtr& update);
00087 void onTau(const auv_msgs::BodyForceReq::ConstPtr& tau);
00091 void onDepth(const std_msgs::Float32::ConstPtr& data);
00095 void onAltitude(const std_msgs::Float32::ConstPtr& data);
00099 void processMeasurements();
00103 void publishState();
00104
00108 KFNav nav;
00112 KFNav::vector tauIn;
00116 KFNav::vector measurements, newMeas;
00120 labust::math::unwrap unwrap;
00124 ros::Publisher stateMeas, stateHat, currentsHat;
00128 ros::Subscriber tauAch, depth, altitude, modelUpdate;
00132 GPSHandler gps;
00136 ImuHandler imu;
00140 DvlHandler dvl;
00144 tf::TransformBroadcaster broadcaster;
00148 double alt;
00152 KFNav::ModelParams params[DoF];
00156 bool useYawRate;
00160 int dvl_model;
00161 };
00162 }
00163 }
00164
00165 #endif