From 2cbac81d5d8cbf353c223451be4a75d9678f3da8 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Wed, 22 Jul 2020 12:51:49 +0530 Subject: [PATCH 1/9] Added Ogre2 implementation for lidar visual Signed-off-by: Mihir Kulkarni --- .../rendering/ogre2/Ogre2LidarVisual.hh | 36 +- ogre2/src/Ogre2LidarVisual.cc | 399 +++++++++++++++++- 2 files changed, 421 insertions(+), 14 deletions(-) diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh index 8d164f51a..2562a5a8c 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh @@ -19,6 +19,7 @@ #define IGNITION_RENDERING_OGRE2_OGRELIDARVISUAL_HH_ #include +#include #include "ignition/rendering/base/BaseLidarVisual.hh" #include "ignition/rendering/ogre2/Ogre2Visual.hh" #include "ignition/rendering/ogre2/Ogre2Scene.hh" @@ -29,9 +30,13 @@ namespace ignition namespace rendering { inline namespace IGNITION_RENDERING_VERSION_NAMESPACE { - /// \brief Ogre 2.x implementation of a marker geometry. + // + // Forward declaration + class Ogre2LidarVisualPrivate; + + /// \brief Ogre implementation of a Lidar Visual. class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2LidarVisual - : public BaseLidarVisual + : public BaseLidarVisual { /// \brief Constructor protected: Ogre2LidarVisual(); @@ -48,8 +53,33 @@ namespace ignition // Documentation inherited. public: virtual void Destroy() override; - /// \brief Marker should only be created by scene. + // Documentation inherited + public: virtual void Update() override; + + // Documentation inherited + public: virtual void SetPoints( + const std::vector &_points) override; + + // Documentation inherited + public: virtual void ClearPoints() override; + + // Documentation inherited + public: virtual unsigned int PointCount() const override; + + // Documentation inherited + public: virtual std::vector Points() const override; + + /// \brief Create the Lidar Visual in ogre + private: void Create(); + + /// \brief Clear data stored by dynamiclines + private: void ClearVisualData(); + + /// \brief Lidar Visual should only be created by scene. private: friend class Ogre2Scene; + + /// \brief Private data class + private: std::unique_ptr dataPtr; }; } } diff --git a/ogre2/src/Ogre2LidarVisual.cc b/ogre2/src/Ogre2LidarVisual.cc index dd51223a3..2fb7f981b 100644 --- a/ogre2/src/Ogre2LidarVisual.cc +++ b/ogre2/src/Ogre2LidarVisual.cc @@ -15,46 +15,423 @@ * */ -#include +#include #include "ignition/rendering/ogre2/Ogre2DynamicRenderable.hh" #include "ignition/rendering/ogre2/Ogre2LidarVisual.hh" -#include "ignition/rendering/ogre2/Ogre2Material.hh" -#include "ignition/rendering/ogre2/Ogre2Mesh.hh" #include "ignition/rendering/ogre2/Ogre2Scene.hh" -#include "ignition/rendering/ogre2/Ogre2Visual.hh" +#include "ignition/rendering/ogre2/Ogre2Marker.hh" +#include "ignition/rendering/ogre2/Ogre2Geometry.hh" + +class ignition::rendering::Ogre2LidarVisualPrivate +{ + /// \brief Non Hitting DynamicLines Object to display + public: std::vector> noHitRayStrips; + + /// \brief Hitting DynamicLines Object to display + public: std::vector> rayStrips; + + /// \brief Dead Zone Geometry DynamicLines Object to display + public: std::vector> deadZoneRayFans; + + /// \brief Lidar Ray DynamicLines Object to display + public: std::vector> rayLines; + + /// \brief Lidar Points DynamicLines Object to display + public: std::vector> points; + + /// \brief Lidar visual type + public: LidarVisualType lidarVisType = + LidarVisualType::LVT_TRIANGLE_STRIPS; + + /// \brief Current value of DisplayNonHitting parameter + public: bool currentDisplayNonHitting = true; + + /// \brief The current lidar points data + public: std::vector lidarPoints; + + /// \brief True if new points data is received + public: bool receivedData = false; +}; using namespace ignition; using namespace rendering; ////////////////////////////////////////////////// Ogre2LidarVisual::Ogre2LidarVisual() + : dataPtr(new Ogre2LidarVisualPrivate) { - // BaseLidarVisual::Init(); } ////////////////////////////////////////////////// Ogre2LidarVisual::~Ogre2LidarVisual() { - // no ops + // no ops +} + +////////////////////////////////////////////////// +void Ogre2LidarVisual::PreRender() +{ + // no ops +} + +////////////////////////////////////////////////// +void Ogre2LidarVisual::Destroy() +{ + BaseLidarVisual::Destroy(); + for (auto ray : this->dataPtr->noHitRayStrips) + { + ray->Clear(); + ray.reset(); + } + + for (auto ray : this->dataPtr->rayStrips) + { + ray->Clear(); + ray.reset(); + } + + for (auto ray : this->dataPtr->rayLines) + { + ray->Clear(); + ray.reset(); + } + + for (auto ray : this->dataPtr->deadZoneRayFans) + { + ray->Clear(); + ray.reset(); + } + + for (auto ray : this->dataPtr->points) + { + ray->Clear(); + ray.reset(); + } + + this->ClearPoints(); } ////////////////////////////////////////////////// void Ogre2LidarVisual::Init() { - BaseLidarVisual::Init(); + BaseLidarVisual::Init(); + this->Create(); } ////////////////////////////////////////////////// -void Ogre2LidarVisual::PreRender() +void Ogre2LidarVisual::Create() { - // no ops + this->ClearPoints(); + this->dataPtr->receivedData = false; } +////////////////////////////////////////////////// +void Ogre2LidarVisual::ClearPoints() +{ + this->dataPtr->lidarPoints.clear(); + this->dataPtr->receivedData = false; +} ////////////////////////////////////////////////// -void Ogre2LidarVisual::Destroy() +void Ogre2LidarVisual::ClearVisualData() { - // no ops + this->dataPtr->noHitRayStrips.clear(); + this->dataPtr->deadZoneRayFans.clear(); + this->dataPtr->rayLines.clear(); + this->dataPtr->rayStrips.clear(); + this->dataPtr->points.clear(); } +////////////////////////////////////////////////// +void Ogre2LidarVisual::SetPoints(const std::vector &_points) +{ + this->dataPtr->lidarPoints = _points; + this->dataPtr->receivedData = true; +} + +////////////////////////////////////////////////// +void Ogre2LidarVisual::Update() +{ + if (!this->dataPtr->receivedData || this->dataPtr->lidarPoints.size() == 0) + { + ignwarn << "New lidar data not received. Exiting update function" + << std::endl; + return; + } + + bool clearVisuals = false; + + if (this->lidarVisualType != this->dataPtr->lidarVisType + || !this->displayNonHitting) + { + clearVisuals = true; + } + + if (this->displayNonHitting != this->dataPtr->currentDisplayNonHitting) + { + clearVisuals = true; + this->dataPtr->currentDisplayNonHitting = this->displayNonHitting; + } + + // if visual type is changed, clear all DynamicLines + if (clearVisuals) + { + this->ClearVisualData(); + } + this->dataPtr->lidarVisType = this->lidarVisualType; + + this->dataPtr->receivedData = false; + double horizontalAngle = this->minHorizontalAngle; + double verticalAngle = this->minVerticalAngle; + + if (this->horizontalCount > 1) + { + this->horizontalAngleStep = + (this->maxHorizontalAngle - this->minHorizontalAngle) / + (this->horizontalCount - 1); + } + + if (this->verticalCount > 1) + { + this->verticalAngleStep = + (this->maxVerticalAngle - this->minVerticalAngle) / + (this->verticalCount - 1); + } + + if (this->dataPtr->lidarPoints.size() != + this->verticalCount * this->horizontalCount) + { + ignwarn << "Size of lidar data inconsistent with rays." + << " Exiting update function." + << std::endl; + return; + } + + // Process each point from received data + // Every line segment, and every triangle is saved separately, + // as a pointer to a DynamicLine + // This initializes and updates only the selected DynamicLine variables + for (unsigned int j = 0; j < this->verticalCount; ++j) + { + horizontalAngle = this->minHorizontalAngle; + + if (this->dataPtr->lidarVisType == LidarVisualType::LVT_RAY_LINES || + this->dataPtr->lidarVisType == LidarVisualType::LVT_TRIANGLE_STRIPS) + { + if (j+1 > this->dataPtr->rayLines.size()) + { + std::shared_ptr renderable = + std::shared_ptr( + new Ogre2DynamicRenderable(this->Scene())); + + renderable->SetOperationType(MT_LINE_LIST); + MaterialPtr mat = this->Scene()->Material("Lidar/BlueRay"); + renderable->SetMaterial(mat, false); + + this->ogreNode->attachObject(renderable->OgreObject()); + this->dataPtr->rayLines.push_back(renderable); + + if (this->dataPtr->lidarVisType == LidarVisualType::LVT_TRIANGLE_STRIPS) + { + renderable = std::shared_ptr( + new Ogre2DynamicRenderable(this->Scene())); + + renderable->SetOperationType(MT_TRIANGLE_STRIP); + mat = this->Scene()->Material("Lidar/LightBlueStrips"); + + renderable->SetMaterial(mat, false); + + this->ogreNode->attachObject(renderable->OgreObject()); + this->dataPtr->noHitRayStrips.push_back(renderable); + + renderable = std::shared_ptr( + new Ogre2DynamicRenderable(this->Scene())); + + renderable->SetOperationType(MT_TRIANGLE_FAN); + mat = this->Scene()->Material("Lidar/TransBlack"); + + renderable->SetMaterial(mat, false); + + this->ogreNode->attachObject(renderable->OgreObject()); + this->dataPtr->deadZoneRayFans.push_back(renderable); + this->dataPtr->deadZoneRayFans[j]->AddPoint( + ignition::math::Vector3d::Zero); + + renderable = std::shared_ptr( + new Ogre2DynamicRenderable(this->Scene())); + + renderable->SetOperationType(MT_TRIANGLE_STRIP); + mat = this->Scene()->Material("Lidar/BlueStrips"); + + renderable->SetMaterial(mat, false); + + this->ogreNode->attachObject(renderable->OgreObject()); + this->dataPtr->rayStrips.push_back(renderable); + } + } + } + + else if (this->dataPtr->lidarVisType == + LidarVisualType::LVT_POINTS) + { + if (j+1 > this->dataPtr->points.size()) + { + std::shared_ptr renderable = + std::shared_ptr( + new Ogre2DynamicRenderable(this->Scene())); + + renderable->SetOperationType(MT_POINTS); + MaterialPtr mat = this->Scene()->Material("Lidar/BlueRay"); + renderable->SetMaterial(mat, false); + + this->ogreNode->attachObject(renderable->OgreObject()); + this->dataPtr->points.push_back(renderable); + } + } + + if (this->dataPtr->lidarVisType == LidarVisualType::LVT_TRIANGLE_STRIPS) + { + this->dataPtr->deadZoneRayFans[j]->SetPoint(0, this->offset.Pos()); + } + + unsigned count = this->horizontalCount; + // Process each ray in current scan + for (unsigned int i = 0; i < count; ++i) + { + // calculate range of the ray + double r = this->dataPtr->lidarPoints[ j * this->horizontalCount + i]; + + bool inf = std::isinf(r); + ignition::math::Quaterniond ray( + ignition::math::Vector3d(0.0, -verticalAngle, horizontalAngle)); + + ignition::math::Vector3d axis = this->offset.Rot() * ray * + ignition::math::Vector3d(1.0, 0.0, 0.0); + + // Check for infinite range, which indicates the ray did not + // intersect an object. + double hitRange = inf ? 0 : r; + + // Compute the start point of the ray + ignition::math::Vector3d startPt = + (axis * minRange) + this->offset.Pos(); + + // Compute the end point of the ray + ignition::math::Vector3d pt = + (axis * hitRange) + this->offset.Pos(); + + double noHitRange = inf ? maxRange : hitRange; + + // Compute the end point of the no-hit ray + ignition::math::Vector3d noHitPt = + (axis * noHitRange) + this->offset.Pos(); + + // Update the lines and strips that represent each simulated ray. + + // For TRIANGLE_STRIPS Lidar Visual to be displayed + if (this->dataPtr->lidarVisType == LidarVisualType::LVT_TRIANGLE_STRIPS + || this->dataPtr->lidarVisType == LidarVisualType::LVT_RAY_LINES) + { + if (i >= this->dataPtr->rayLines[j]->PointCount()/2) + { + if (this->displayNonHitting || !inf) + { + this->dataPtr->rayLines[j]->AddPoint(startPt); + this->dataPtr->rayLines[j]->AddPoint(inf ? noHitPt: pt); + } + + if (this->dataPtr->lidarVisType == + LidarVisualType::LVT_TRIANGLE_STRIPS) + { + this->dataPtr->rayStrips[j]->AddPoint(startPt); + this->dataPtr->rayStrips[j]->AddPoint(inf ? startPt : pt); + + this->dataPtr->noHitRayStrips[j]->AddPoint(startPt); + this->dataPtr->noHitRayStrips[j]->AddPoint( + inf ? (this->displayNonHitting? noHitPt: startPt) : pt); + } + } + else + { + if (this->displayNonHitting || !inf) + { + this->dataPtr->rayLines[j]->SetPoint(i*2, startPt); + this->dataPtr->rayLines[j]->SetPoint(i*2+1, inf ? noHitPt: pt); + } + + if (this->dataPtr->lidarVisType == + LidarVisualType::LVT_TRIANGLE_STRIPS) + { + this->dataPtr->rayStrips[j]->SetPoint(i*2, startPt); + this->dataPtr->rayStrips[j]->SetPoint(i*2+1, inf? startPt : pt); + + this->dataPtr->noHitRayStrips[j]->SetPoint(i*2, startPt); + this->dataPtr->noHitRayStrips[j]->SetPoint(i*2+1, + inf ? (this->displayNonHitting? noHitPt: startPt) : pt); + } + } + if (this->dataPtr->lidarVisType == LidarVisualType::LVT_TRIANGLE_STRIPS) + { + // Draw the triangle fan that indicates the dead zone. + if (i+1 >= this->dataPtr->deadZoneRayFans[j]->PointCount()) + this->dataPtr->deadZoneRayFans[j]->AddPoint(startPt); + else + this->dataPtr->deadZoneRayFans[j]->SetPoint(i+1, startPt); + } + } + + // For POINTS Lidar Visual to be displayed + else if (this->dataPtr->lidarVisType == + LidarVisualType::LVT_POINTS) + { + if (i >= this->dataPtr->points[j]->PointCount()) + { + if (this->displayNonHitting || !inf) + { + this->dataPtr->points[j]->AddPoint(inf ? noHitPt: pt); + } + } + else + { + if (this->displayNonHitting || !inf) + { + this->dataPtr->points[j]->SetPoint(i, inf ? noHitPt: pt); + } + } + } + horizontalAngle += this->horizontalAngleStep; + } + + // Update the DynamicLines pointers after adding points based on type + if (this->dataPtr->lidarVisType == LidarVisualType::LVT_TRIANGLE_STRIPS + || this->dataPtr->lidarVisType == LidarVisualType::LVT_RAY_LINES) + { + this->dataPtr->rayLines[j]->Update(); + if (this->dataPtr->lidarVisType == + LidarVisualType::LVT_TRIANGLE_STRIPS) + { + this->dataPtr->rayStrips[j]->Update(); + this->dataPtr->noHitRayStrips[j]->Update(); + this->dataPtr->deadZoneRayFans[j]->Update(); + } + } + else if (this->dataPtr->lidarVisType == LidarVisualType::LVT_POINTS) + { + this->dataPtr->points[j]->Update(); + } + verticalAngle += this->verticalAngleStep; + } +} + +////////////////////////////////////////////////// +unsigned int Ogre2LidarVisual::PointCount() const +{ + return this->dataPtr->lidarPoints.size(); +} + +////////////////////////////////////////////////// +std::vector Ogre2LidarVisual::Points() const +{ + return this->dataPtr->lidarPoints; +} From d6196590121251382637165c741346696d4b6866 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Wed, 22 Jul 2020 12:52:11 +0530 Subject: [PATCH 2/9] Changed Colour Signed-off-by: Mihir Kulkarni --- .../rendering/base/BaseLidarVisual.hh | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/include/ignition/rendering/base/BaseLidarVisual.hh b/include/ignition/rendering/base/BaseLidarVisual.hh index 4ae482b27..e4bd82bc4 100644 --- a/include/ignition/rendering/base/BaseLidarVisual.hh +++ b/include/ignition/rendering/base/BaseLidarVisual.hh @@ -444,22 +444,27 @@ namespace ignition mtl = this->Scene()->CreateMaterial("Lidar/BlueStrips"); mtl->SetAmbient(0.0, 0.0, 1.0); mtl->SetDiffuse(0.0, 0.0, 1.0); + mtl->SetEmissive(0.0, 0.0, 1.0); mtl->SetTransparency(0.4); mtl->SetCastShadows(false); mtl->SetReceiveShadows(false); mtl->SetLightingEnabled(false); + mtl->SetMetalness(0.0); + mtl->SetReflectivity(0.0); } if (!this->Scene()->MaterialRegistered("Lidar/LightBlueStrips")) { mtl = this->Scene()->CreateMaterial("Lidar/LightBlueStrips"); - mtl->SetAmbient(0.5, 0.5, 1.0); - mtl->SetDiffuse(0.5, 0.5, 1.0); - mtl->SetEmissive(0.5, 0.5, 1.0); + mtl->SetAmbient(0.0, 0.0, 1.0); + mtl->SetDiffuse(0.0, 0.0, 1.0); + mtl->SetEmissive(0.0, 0.0, 1.0); mtl->SetTransparency(0.8); mtl->SetCastShadows(false); mtl->SetReceiveShadows(false); mtl->SetLightingEnabled(false); + mtl->SetMetalness(0.0); + mtl->SetReflectivity(0.0); } if (!this->Scene()->MaterialRegistered("Lidar/TransBlack")) @@ -468,10 +473,12 @@ namespace ignition mtl->SetAmbient(0.0, 0.0, 0.0); mtl->SetDiffuse(0.0, 0.0, 0.0); mtl->SetEmissive(0.0, 0.0, 0.0); - mtl->SetTransparency(0.7); + mtl->SetTransparency(0.4); mtl->SetCastShadows(false); mtl->SetReceiveShadows(false); mtl->SetLightingEnabled(false); + mtl->SetMetalness(0.5); + mtl->SetReflectivity(0.2); } if (!this->Scene()->MaterialRegistered("Lidar/BlueRay")) @@ -480,11 +487,13 @@ namespace ignition mtl->SetAmbient(0.0, 0.0, 1.0); mtl->SetDiffuse(0.0, 0.0, 1.0); mtl->SetEmissive(0.0, 0.0, 1.0); - mtl->SetSpecular(0.1, 0.1, 1); + mtl->SetSpecular(0.0, 0.0, 1.0); mtl->SetTransparency(0.0); mtl->SetCastShadows(false); mtl->SetReceiveShadows(false); mtl->SetLightingEnabled(false); + mtl->SetMetalness(0.1); + mtl->SetReflectivity(0.2); } return; } From 4dc44446c1c7be29d9b58820d713c887b16f0555 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Wed, 22 Jul 2020 12:52:35 +0530 Subject: [PATCH 3/9] Minor changes, addded tests for Ogre2 Signed-off-by: Mihir Kulkarni --- examples/lidar_visual/Main.cc | 2 +- test/integration/lidar_visual.cc | 22 ---------------------- 2 files changed, 1 insertion(+), 23 deletions(-) diff --git a/examples/lidar_visual/Main.cc b/examples/lidar_visual/Main.cc index 56b067e9b..16d5a823d 100644 --- a/examples/lidar_visual/Main.cc +++ b/examples/lidar_visual/Main.cc @@ -219,7 +219,7 @@ LidarVisualPtr createLidar(ScenePtr _scene) // LVT_RAY_LINES -> Lines along the lidar sensor to the obstacle // LVT_TRIANGLE_STRIPS -> Coloured triangle strips denoting hitting and // non-hitting parts of the scan - lidar->SetType(LidarVisualType::LVT_RAY_LINES); + lidar->SetType(LidarVisualType::LVT_TRIANGLE_STRIPS); lidar->SetPoints(pts); VisualPtr root = _scene->RootVisual(); diff --git a/test/integration/lidar_visual.cc b/test/integration/lidar_visual.cc index 8c3d6a964..713c31dab 100644 --- a/test/integration/lidar_visual.cc +++ b/test/integration/lidar_visual.cc @@ -72,13 +72,6 @@ void LidarVisualTest::Configure(const std::string &_renderEngine) return; } - if (_renderEngine == "ogre2") - { - igndbg << "LidarVisual not supported yet in rendering engine: " - << _renderEngine << std::endl; - return; - } - // create and populate scene RenderEngine *engine = rendering::engine(_renderEngine); if (!engine) @@ -177,14 +170,6 @@ void LidarVisualTest::RaysUnitBox(const std::string &_renderEngine) return; } - if (_renderEngine == "ogre2") - { - igndbg << "LidarVisual not supported yet in rendering engine: " - << _renderEngine << std::endl; - return; - } - - // Test lidar visual with 3 boxes in the world, using reading from GPU rays // First GPU rays at identity orientation, second at 90 degree roll // First place 2 of 3 boxes within range and verify range values from lidar. @@ -427,13 +412,6 @@ void LidarVisualTest::LaserVertical(const std::string &_renderEngine) return; } - if (_renderEngine == "ogre2") - { - igndbg << "LidarVisual not supported yet in rendering engine: " - << _renderEngine << std::endl; - return; - } - // Test a rays that has a vertical range component. // Place a box within range and verify range values, // then move the box out of range and verify range values From ce843e0d98be59b7dfd1c37afb242fe45fe3d5e3 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Wed, 22 Jul 2020 12:58:40 +0530 Subject: [PATCH 4/9] Edited Changelog Signed-off-by: Mihir Kulkarni --- Changelog.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Changelog.md b/Changelog.md index fbfeb1a06..042ad0b6f 100644 --- a/Changelog.md +++ b/Changelog.md @@ -6,6 +6,9 @@ ### Ignition Rendering 4.0.0 +1. Added Lidar Visual for Ogre2 + * [Pull request #116](https://github.com/ignitionrobotics/ign-rendering/pull/116) + 1. Added Lidar Visual Types for Ogre1 * [Pull request #114](https://github.com/ignitionrobotics/ign-rendering/pull/114) From 338c1a9173114ea13807fc8b9163652654c6537f Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Thu, 23 Jul 2020 11:43:44 +0530 Subject: [PATCH 5/9] minor changes Signed-off-by: Mihir Kulkarni --- examples/lidar_visual/Main.cc | 2 +- ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/lidar_visual/Main.cc b/examples/lidar_visual/Main.cc index 16d5a823d..0935976bf 100644 --- a/examples/lidar_visual/Main.cc +++ b/examples/lidar_visual/Main.cc @@ -43,7 +43,7 @@ const std::string RESOURCE_PATH = const double hMinAngle = -2.26889; const double hMaxAngle = 2.26889; const double vMinAngle = 0; -const double vMaxAngle = 0.1; +const double vMaxAngle = 0; const double minRange = 0.08; const double maxRange = 10.0; const int hRayCount = 640; diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh index 2562a5a8c..a93639030 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh @@ -34,7 +34,7 @@ namespace ignition // Forward declaration class Ogre2LidarVisualPrivate; - /// \brief Ogre implementation of a Lidar Visual. + /// \brief Ogre 2.x implementation of a Lidar Visual. class IGNITION_RENDERING_OGRE2_VISIBLE Ogre2LidarVisual : public BaseLidarVisual { From 8d4e7a7ae88035328dfd1146a5710a49e96c3998 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Wed, 29 Jul 2020 16:53:41 +0530 Subject: [PATCH 6/9] added ClearVisual function Signed-off-by: Mihir Kulkarni --- examples/lidar_visual/GlutWindow.cc | 25 ++++++++++++++----- include/ignition/rendering/LidarVisual.hh | 3 +++ .../rendering/base/BaseLidarVisual.hh | 10 ++++++++ .../rendering/ogre/OgreLidarVisual.hh | 3 +++ ogre/src/OgreLidarVisual.cc | 12 +++++++++ .../rendering/ogre2/Ogre2LidarVisual.hh | 3 +++ ogre2/src/Ogre2LidarVisual.cc | 12 +++++++++ 7 files changed, 62 insertions(+), 6 deletions(-) diff --git a/examples/lidar_visual/GlutWindow.cc b/examples/lidar_visual/GlutWindow.cc index 78dd83144..5f4b7b5fc 100644 --- a/examples/lidar_visual/GlutWindow.cc +++ b/examples/lidar_visual/GlutWindow.cc @@ -62,7 +62,7 @@ unsigned int g_cameraIndex = 0; ir::ImagePtr g_image; bool g_initContext = false; - +bool g_clear = false; std::vector g_lidarData; ir::LidarVisualPtr g_lidar; bool g_lidarVisualUpdateDirty = false; @@ -249,12 +249,19 @@ void updateLidarVisual() // change detected due to key press if (g_lidarVisualUpdateDirty) { - g_lidar->SetDisplayNonHitting(g_showNonHitting); - g_lidar->SetPoints(g_lidarData); - g_lidar->SetType(g_lidarVisType); - g_lidar->Update(); + if(g_clear == true) + { + g_lidar->ClearVisual(); + } + else + { + g_lidar->SetDisplayNonHitting(g_showNonHitting); + g_lidar->SetPoints(g_lidarData); + g_lidar->SetType(g_lidarVisType); + g_lidar->Update(); + } g_lidarVisualUpdateDirty = false; - + g_clear = false; g_time = std::chrono::steady_clock::now() - g_startTime; prevUpdateTime = std::chrono::duration_cast( g_time).count(); @@ -333,6 +340,11 @@ void keyboardCB(unsigned char _key, int, int) g_showNonHitting = !g_showNonHitting; g_lidarVisualUpdateDirty = true; } + else if (_key == 'c' || _key == 'C') + { + g_clear = true; + g_lidarVisualUpdateDirty = true; + } else if (_key == '0') { g_lidarVisType = LidarVisualType::LVT_NONE; @@ -412,6 +424,7 @@ void printUsage() std::cout << " ESC - Exit " << std::endl; std::cout << " " << std::endl; std::cout << " H: Toggle display for non-hitting rays " << std::endl; + std::cout << " C: Clear Visual " << std::endl; std::cout << " " << std::endl; std::cout << " 0: Do not display visual " << std::endl; std::cout << " 1: Display ray lines visual " << std::endl; diff --git a/include/ignition/rendering/LidarVisual.hh b/include/ignition/rendering/LidarVisual.hh index 812410940..951fd8215 100644 --- a/include/ignition/rendering/LidarVisual.hh +++ b/include/ignition/rendering/LidarVisual.hh @@ -63,6 +63,9 @@ namespace ignition /// \brief Clear the points of the lidar visual public: virtual void ClearPoints() = 0; + /// \brief Clear the lidar visual + public: virtual void ClearVisual() = 0; + /// \brief Update the Visual public: virtual void Update() = 0; diff --git a/include/ignition/rendering/base/BaseLidarVisual.hh b/include/ignition/rendering/base/BaseLidarVisual.hh index e4bd82bc4..89a4f5919 100644 --- a/include/ignition/rendering/base/BaseLidarVisual.hh +++ b/include/ignition/rendering/base/BaseLidarVisual.hh @@ -50,6 +50,9 @@ namespace ignition // Documentation inherited public: virtual void ClearPoints() override; + // Documentation inherited + public: virtual void ClearVisual() override; + // Documentation inherited public: virtual void SetPoints( const std::vector &_points) override; @@ -218,6 +221,13 @@ namespace ignition // no op } + ///////////////////////////////////////////////// + template + void BaseLidarVisual::ClearVisual() + { + // no op + } + ///////////////////////////////////////////////// template unsigned int BaseLidarVisual::PointCount() const diff --git a/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh b/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh index de93f234f..c15b0a077 100644 --- a/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh +++ b/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh @@ -63,6 +63,9 @@ namespace ignition // Documentation inherited public: virtual void ClearPoints() override; + // Documentation inherited + public: virtual void ClearVisual() override; + // Documentation inherited public: virtual unsigned int PointCount() const override; diff --git a/ogre/src/OgreLidarVisual.cc b/ogre/src/OgreLidarVisual.cc index 5e8d6145c..f60e1fef0 100644 --- a/ogre/src/OgreLidarVisual.cc +++ b/ogre/src/OgreLidarVisual.cc @@ -154,6 +154,12 @@ void OgreLidarVisual::SetPoints(const std::vector &_points) ////////////////////////////////////////////////// void OgreLidarVisual::Update() { + if (this->lidarVisualType == LidarVisualType::LVT_NONE) + { + this->ClearVisualData(); + return; + } + if (!this->dataPtr->receivedData || this->dataPtr->lidarPoints.size() == 0) { ignwarn << "New lidar data not received. Exiting update function" @@ -457,3 +463,9 @@ std::vector OgreLidarVisual::Points() const { return this->dataPtr->lidarPoints; } + +////////////////////////////////////////////////// +void OgreLidarVisual::ClearVisual() +{ + this->ClearVisualData(); +} diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh index a93639030..5a6d2a5f6 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh @@ -63,6 +63,9 @@ namespace ignition // Documentation inherited public: virtual void ClearPoints() override; + // Documentation inherited + public: virtual void ClearVisual() override; + // Documentation inherited public: virtual unsigned int PointCount() const override; diff --git a/ogre2/src/Ogre2LidarVisual.cc b/ogre2/src/Ogre2LidarVisual.cc index 2fb7f981b..8538a90a2 100644 --- a/ogre2/src/Ogre2LidarVisual.cc +++ b/ogre2/src/Ogre2LidarVisual.cc @@ -153,6 +153,12 @@ void Ogre2LidarVisual::SetPoints(const std::vector &_points) ////////////////////////////////////////////////// void Ogre2LidarVisual::Update() { + if (this->lidarVisualType == LidarVisualType::LVT_NONE) + { + this->ClearVisualData(); + return; + } + if (!this->dataPtr->receivedData || this->dataPtr->lidarPoints.size() == 0) { ignwarn << "New lidar data not received. Exiting update function" @@ -435,3 +441,9 @@ std::vector Ogre2LidarVisual::Points() const { return this->dataPtr->lidarPoints; } + +////////////////////////////////////////////////// +void Ogre2LidarVisual::ClearVisual() +{ + this->ClearVisualData(); +} From 03ac1688c3a34762ac9ea7db22deae9d2da906c2 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Wed, 29 Jul 2020 18:30:52 +0530 Subject: [PATCH 7/9] fix linter error MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Mihir Kulkarni --- examples/lidar_visual/GlutWindow.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/lidar_visual/GlutWindow.cc b/examples/lidar_visual/GlutWindow.cc index 5f4b7b5fc..c7301e7d4 100644 --- a/examples/lidar_visual/GlutWindow.cc +++ b/examples/lidar_visual/GlutWindow.cc @@ -249,7 +249,7 @@ void updateLidarVisual() // change detected due to key press if (g_lidarVisualUpdateDirty) { - if(g_clear == true) + if (g_clear == true) { g_lidar->ClearVisual(); } From 2cafdb082c717fd9effe116d2c610914c43eb2f2 Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Tue, 4 Aug 2020 19:56:54 +0530 Subject: [PATCH 8/9] ClearPoints function clears visual, removed ClearVisual function Signed-off-by: Mihir Kulkarni --- include/ignition/rendering/LidarVisual.hh | 3 --- include/ignition/rendering/base/BaseLidarVisual.hh | 10 ---------- .../include/ignition/rendering/ogre/OgreLidarVisual.hh | 3 --- ogre/src/OgreLidarVisual.cc | 7 +------ .../ignition/rendering/ogre2/Ogre2LidarVisual.hh | 3 --- ogre2/src/Ogre2LidarVisual.cc | 7 +------ 6 files changed, 2 insertions(+), 31 deletions(-) diff --git a/include/ignition/rendering/LidarVisual.hh b/include/ignition/rendering/LidarVisual.hh index 951fd8215..812410940 100644 --- a/include/ignition/rendering/LidarVisual.hh +++ b/include/ignition/rendering/LidarVisual.hh @@ -63,9 +63,6 @@ namespace ignition /// \brief Clear the points of the lidar visual public: virtual void ClearPoints() = 0; - /// \brief Clear the lidar visual - public: virtual void ClearVisual() = 0; - /// \brief Update the Visual public: virtual void Update() = 0; diff --git a/include/ignition/rendering/base/BaseLidarVisual.hh b/include/ignition/rendering/base/BaseLidarVisual.hh index 89a4f5919..e4bd82bc4 100644 --- a/include/ignition/rendering/base/BaseLidarVisual.hh +++ b/include/ignition/rendering/base/BaseLidarVisual.hh @@ -50,9 +50,6 @@ namespace ignition // Documentation inherited public: virtual void ClearPoints() override; - // Documentation inherited - public: virtual void ClearVisual() override; - // Documentation inherited public: virtual void SetPoints( const std::vector &_points) override; @@ -221,13 +218,6 @@ namespace ignition // no op } - ///////////////////////////////////////////////// - template - void BaseLidarVisual::ClearVisual() - { - // no op - } - ///////////////////////////////////////////////// template unsigned int BaseLidarVisual::PointCount() const diff --git a/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh b/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh index c15b0a077..de93f234f 100644 --- a/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh +++ b/ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh @@ -63,9 +63,6 @@ namespace ignition // Documentation inherited public: virtual void ClearPoints() override; - // Documentation inherited - public: virtual void ClearVisual() override; - // Documentation inherited public: virtual unsigned int PointCount() const override; diff --git a/ogre/src/OgreLidarVisual.cc b/ogre/src/OgreLidarVisual.cc index f60e1fef0..66cc126bf 100644 --- a/ogre/src/OgreLidarVisual.cc +++ b/ogre/src/OgreLidarVisual.cc @@ -131,6 +131,7 @@ void OgreLidarVisual::Create() void OgreLidarVisual::ClearPoints() { this->dataPtr->lidarPoints.clear(); + this->ClearVisualData(); this->dataPtr->receivedData = false; } @@ -463,9 +464,3 @@ std::vector OgreLidarVisual::Points() const { return this->dataPtr->lidarPoints; } - -////////////////////////////////////////////////// -void OgreLidarVisual::ClearVisual() -{ - this->ClearVisualData(); -} diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh index 5a6d2a5f6..a93639030 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2LidarVisual.hh @@ -63,9 +63,6 @@ namespace ignition // Documentation inherited public: virtual void ClearPoints() override; - // Documentation inherited - public: virtual void ClearVisual() override; - // Documentation inherited public: virtual unsigned int PointCount() const override; diff --git a/ogre2/src/Ogre2LidarVisual.cc b/ogre2/src/Ogre2LidarVisual.cc index 8538a90a2..3ecd37d59 100644 --- a/ogre2/src/Ogre2LidarVisual.cc +++ b/ogre2/src/Ogre2LidarVisual.cc @@ -130,6 +130,7 @@ void Ogre2LidarVisual::Create() void Ogre2LidarVisual::ClearPoints() { this->dataPtr->lidarPoints.clear(); + this->ClearVisualData(); this->dataPtr->receivedData = false; } @@ -441,9 +442,3 @@ std::vector Ogre2LidarVisual::Points() const { return this->dataPtr->lidarPoints; } - -////////////////////////////////////////////////// -void Ogre2LidarVisual::ClearVisual() -{ - this->ClearVisualData(); -} From cb470cce8e2d31b4e2b0b0ef9716e1af671b347a Mon Sep 17 00:00:00 2001 From: Mihir Kulkarni Date: Tue, 4 Aug 2020 20:08:23 +0530 Subject: [PATCH 9/9] updated example Signed-off-by: Mihir Kulkarni --- examples/lidar_visual/GlutWindow.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/lidar_visual/GlutWindow.cc b/examples/lidar_visual/GlutWindow.cc index c7301e7d4..51f51cdb7 100644 --- a/examples/lidar_visual/GlutWindow.cc +++ b/examples/lidar_visual/GlutWindow.cc @@ -251,7 +251,7 @@ void updateLidarVisual() { if (g_clear == true) { - g_lidar->ClearVisual(); + g_lidar->ClearPoints(); } else {