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