Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #ifndef GPSSENSOR_H_
00014 #define GPSSENSOR_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 #include "osgOceanScene.h"
00023 #include <tf/transform_datatypes.h>
00024
00025 class GPSSensor
00026 {
00027
00028 public:
00029 std::string name,parentLinkName;
00030
00038 GPSSensor(osgOceanScene *oscene, std::string sensor_name, std::string parentName, osg::Node *parent, osg::Matrixd rMl, double std = 0) :
00039 name(sensor_name),parentLinkName(parentName), oscene_(oscene), parent_(parent), rMl_(rMl), std_(std)
00040 {
00041 node_ = new osg::Node();
00042 parent->asGroup()->addChild(node_);
00043 }
00044
00045 osg::Vec3d getMeasurement();
00046 int getTFTransform(tf::Pose & pose, std::string & parent);
00047
00048 double getStandardDeviation()
00049 {
00050 return std_;
00051 }
00052
00054 double depthBelowWater();
00055
00056 virtual ~GPSSensor()
00057 {
00058 }
00059
00060 private:
00061 osg::ref_ptr<osgOceanScene> oscene_;
00062 osg::ref_ptr<osg::Node> parent_;
00063 osg::Matrixd rMl_;
00064 double std_;
00065 osg::ref_ptr<osg::Node> node_;
00066
00067 boost::mt19937 rng_;
00068 };
00069
00070 #endif