Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <uwsim/UWSimUtils.h>
00014 #include <uwsim/DVLSensor.h>
00015 #include <osg/io_utils>
00016
00017 #include <osg/PositionAttitudeTransform>
00018
00019 osg::Vec3d DVLSensor::getMeasurement()
00020 {
00021
00022 boost::shared_ptr<osg::Matrix> rMs = getWorldCoords(node_);
00023 osg::Matrixd lMs = *rMs * osg::Matrixd::inverse(rMl_);
00024 osg::Vec3d x = lMs.getTrans();
00025
00026 ros::Time tnow = ros::Time::now();
00027 ros::Duration ellapsed_time = tnow - tprevious_;
00028 tprevious_ = tnow;
00029
00030
00031 osg::Vec3d v = (x - xprevious_) / ellapsed_time.toSec();
00032 xprevious_ = x;
00033
00034
00035 osg::Matrixd sRl = osg::Matrixd::inverse(lMs);
00036 sRl.setTrans(0, 0, 0);
00037 osg::Vec4d vh(v.x(), v.y(), v.z(), 1);
00038 osg::Vec4d vdvl = vh * sRl;
00039
00040
00041 static boost::normal_distribution<> normal(0, std_);
00042 static boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor(rng_, normal);
00043 vdvl[0] += var_nor();
00044 vdvl[1] += var_nor();
00045 vdvl[2] += var_nor();
00046
00047 return osg::Vec3d(vdvl.x(), vdvl.y(), vdvl.z());
00048 }
00049
00050 int DVLSensor::getTFTransform(tf::Pose & pose, std::string & parent){
00051 parent=parentLinkName;
00052 pose.setOrigin(tf::Vector3(parent_->asTransform()->asPositionAttitudeTransform()->getPosition().x(),
00053 parent_->asTransform()->asPositionAttitudeTransform()->getPosition().y(),
00054 parent_->asTransform()->asPositionAttitudeTransform()->getPosition().z()));
00055 pose.setRotation( tf::Quaternion(parent_->asTransform()->asPositionAttitudeTransform()->getAttitude().x(),
00056 parent_->asTransform()->asPositionAttitudeTransform()->getAttitude().y(),
00057 parent_->asTransform()->asPositionAttitudeTransform()->getAttitude().z(),
00058 parent_->asTransform()->asPositionAttitudeTransform()->getAttitude().w()));
00059 return 1;
00060
00061 }
00062