Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
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
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
00041
00042
00043 mEnd = mStart;
00044 mEnd.preMultTranslate(osg::Vec3d(range, 0, 0));
00045
00046
00047
00048 intersector->reset();
00049 intersector->setStart(mStart.getTrans());
00050 intersector->setEnd(mEnd.getTrans());
00051
00052 root->accept(intersectVisitor);
00053
00054
00055
00056
00057 if (intersector->containsIntersections())
00058 {
00059 osgUtil::LineSegmentIntersector::Intersection intersection = intersector->getFirstIntersection();
00060 osg::Vec3d worldIntPoint = intersection.getWorldIntersectPoint();
00061
00062
00063
00064 distance_to_obstacle = (worldIntPoint - mStart.getTrans()).length();
00065
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;
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