DVLSensor.h
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2013 University of Jaume-I.
00003  * All rights reserved. This program and the accompanying materials
00004  * are made available under the terms of the GNU Public License v3.0
00005  * which accompanies this distribution, and is available at
00006  * http://www.gnu.org/licenses/gpl.html
00007  * 
00008  * Contributors:
00009  *     Mario Prats
00010  *     Javier Perez
00011  */
00012 
00013 #ifndef DVLSENSOR_H_
00014 #define DVLSENSOR_H_
00015 
00016 #include <osg/Node>
00017 #include <osg/Matrix>
00018 #include <osg/Group>
00019 #include <osg/Vec3d>
00020 
00021 #include <boost/random.hpp>
00022 
00023 #include <ros/ros.h>
00024 
00025 class DVLSensor
00026 {
00027 
00028 public:
00029   std::string name;
00030 
00037   DVLSensor(std::string sensor_name, osg::Node *parent, osg::Matrixd rMl, double std = 0) :
00038       name(sensor_name), parent_(parent), rMl_(rMl), std_(std)
00039   {
00040     node_ = new osg::Node();
00041     parent->asGroup()->addChild(node_);
00042     tprevious_ = ros::Time::now();
00043   }
00044 
00045   osg::Vec3d getMeasurement();
00046 
00047   double getStandardDeviation()
00048   {
00049     return std_;
00050   }
00051 
00052   virtual ~DVLSensor()
00053   {
00054   }
00055 
00056 private:
00057   osg::ref_ptr<osg::Node> parent_;
00058   osg::Matrixd rMl_;
00059   double std_;
00060   osg::ref_ptr<osg::Node> node_;
00061   ros::Time tprevious_;
00062   osg::Vec3d xprevious_;
00063 
00064   boost::mt19937 rng_; 
00065 };
00066 
00067 #endif /* DVLSENSOR_H_ */


uwsim
Author(s): Mario Prats
autogenerated on Mon Oct 6 2014 08:24:07