EKF3D.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * EKF3D.cpp
00003  *
00004  *  Created on: 
00005  *      Author: Dula Nad
00006  *      
00007  *  Modified by: Filip Mandic
00008  *
00009  ********************************************************************/
00010 /*********************************************************************
00011  * Software License Agreement (BSD License)
00012  *
00013  *  Copyright (c) 2014, LABUST, UNIZG-FER
00014  *  All rights reserved.
00015  *
00016  *  Redistribution and use in source and binary forms, with or without
00017  *  modification, are permitted provided that the following conditions
00018  *  are met:
00019  *
00020  *   * Redistributions of source code must retain the above copyright
00021  *     notice, this list of conditions and the following disclaimer.
00022  *   * Redistributions in binary form must reproduce the above
00023  *     copyright notice, this list of conditions and the following
00024  *     disclaimer in the documentation and/or other materials provided
00025  *     with the distribution.
00026  *   * Neither the name of the LABUST nor the names of its
00027  *     contributors may be used to endorse or promote products derived
00028  *     from this software without specific prior written permission.
00029  *
00030  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00031  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00032  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00033  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00034  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00035  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00036  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00037  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00038  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00039  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00040  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00041  *  POSSIBILITY OF SUCH DAMAGE.
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> // Dodano
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 /* EKF3D_HPP_ */
00218 #endif


labust_navigation
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:23:33