VirtualRangeSensor.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 VirtualRangeSensor_H_
00014 #define VirtualRangeSensor_H_
00015 
00016 #include "SimulatorConfig.h"
00017 #include "CustomWidget.h"
00018 #include "ConfigXMLParser.h"
00019 
00020 #include <osgViewer/Viewer>
00021 #include <osgGA/NodeTrackerManipulator>
00022 #include <osg/Camera>
00023 #include <osg/Texture2D>
00024 #include <osgGA/GUIEventHandler>
00025 #include <osg/Geometry>
00026 #include <osg/Geode>
00027 #include <osg/NodeTrackerCallback>
00028 #include <osgUtil/IntersectionVisitor>
00029 #include <osgUtil/LineSegmentIntersector>
00030 
00031 //Node tracker that updates the ray coordinates from the tracked node position and computes intersections
00032 class IntersectorUpdateCallback : public osg::NodeTrackerCallback
00033 {
00034   virtual void operator()(osg::Node *node, osg::NodeVisitor *nv)
00035   {
00036     osg::Matrixd mStart, mEnd;
00037     mStart = osg::computeLocalToWorld(nv->getNodePath());
00038     traverse(node, nv);
00039 
00040     //osg::Timer_t startTick = osg::Timer::instance()->tick();
00041 
00042     //update ray and compute intersections. Checks intersections along X axis of the local frame
00043     mEnd = mStart;
00044     mEnd.preMultTranslate(osg::Vec3d(range, 0, 0));
00045 
00046     //std::cerr << "mStart: " << mStart.getTrans().x() << " " << mStart.getTrans().y() << " " << mStart.getTrans().z() << std::endl;
00047     //std::cerr << "mEnd: " << mEnd.getTrans().x() << " " << mEnd.getTrans().y() << " " << mEnd.getTrans().z() << std::endl;
00048     intersector->reset();
00049     intersector->setStart(mStart.getTrans());
00050     intersector->setEnd(mEnd.getTrans());
00051 
00052     root->accept(intersectVisitor);
00053 
00054     //osg::Timer_t endTick = osg::Timer::instance()->tick();
00055     //std::cout<<"Completed in "<<osg::Timer::instance()->delta_s(startTick,endTick)<<std::endl;
00056 
00057     if (intersector->containsIntersections())
00058     {
00059       osgUtil::LineSegmentIntersector::Intersection intersection = intersector->getFirstIntersection();
00060       osg::Vec3d worldIntPoint = intersection.getWorldIntersectPoint();
00061       //osg::Vec3d localIntPoint=intersection.getLocalIntersectPoint();
00062       //std::cerr << "Intersection point(world): " << worldIntPoint.x() << " " << worldIntPoint.y() << " " << worldIntPoint.z() << std::endl;
00063       //std::cerr << "Intersection point(local): " << localIntPoint.x() << " " << localIntPoint.y() << " " << worldIntPoint.z() << std::endl;
00064       distance_to_obstacle = (worldIntPoint - mStart.getTrans()).length();
00065       //std::cerr << "Distance to obstacle: " << distance_to_obstacle << std::endl;
00066     }
00067     else
00068       distance_to_obstacle = range;
00069   }
00070 public:
00071   double range, distance_to_obstacle;
00072   osg::ref_ptr<osg::Node> root;
00073   osg::ref_ptr<osgUtil::LineSegmentIntersector> intersector;
00074   osgUtil::IntersectionVisitor intersectVisitor;
00075 
00076   osg::ref_ptr<osg::Geode> geode; //Geometry node that draws the beam
00077   osg::ref_ptr<osg::Geometry> beam;
00078 
00079   IntersectorUpdateCallback(double range, bool visible, osg::Node *root)
00080   {
00081     this->range = range;
00082     this->distance_to_obstacle = range;
00083     this->root = root;
00084     intersector = new osgUtil::LineSegmentIntersector(osg::Vec3d(0, 0, 0), osg::Vec3d(0, 0, 0));
00085     intersectVisitor.setIntersector(intersector.get());
00086 
00087     if (visible)
00088     {
00089       beam = osg::ref_ptr<osg::Geometry>(new osg::Geometry);
00090       osg::ref_ptr<osg::Vec3Array> points = new osg::Vec3Array;
00091       osg::Vec3d start(0, 0, 0);
00092       osg::Vec3d end(range, 0, 0);
00093       points->push_back(start);
00094       points->push_back(end);
00095       osg::ref_ptr<osg::Vec4Array> color = new osg::Vec4Array;
00096       color->push_back(osg::Vec4(0.0, 1.0, 0.0, 0.6));
00097       beam->setVertexArray(points.get());
00098       beam->setColorArray(color.get());
00099       beam->setColorBinding(osg::Geometry::BIND_PER_PRIMITIVE);
00100       beam->addPrimitiveSet(new osg::DrawArrays(GL_LINES, 0, 2));
00101       geode = osg::ref_ptr<osg::Geode>(new osg::Geode());
00102       geode->addDrawable(beam.get());
00103     }
00104   }
00105 };
00106 
00108 class VirtualRangeSensor
00109 {
00110 public:
00111   std::string name;
00112   osg::ref_ptr<osg::Node> trackNode;
00113   osg::ref_ptr<osg::Node> root;
00114   double range; 
00115   bool visible; 
00116   osg::ref_ptr<IntersectorUpdateCallback> node_tracker;
00117 
00118   VirtualRangeSensor(std::string name, osg::Node *root, osg::Node *trackNode, double range, bool visible);
00119   VirtualRangeSensor();
00120 
00121   virtual void init(std::string name, osg::Node *root, osg::Node *trackNode, double range, bool visible);
00122 
00123 };
00124 
00125 #endif /* VirtualRangeSensor_H_ */


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