From 023c4b487edcffa7aeab00186b1356a6226b6956 Mon Sep 17 00:00:00 2001 From: Utkarsh Date: Tue, 13 Aug 2024 22:39:29 +0530 Subject: [PATCH] Visualize Frustum --- include/gz/rendering/FrustumVisual.hh | 180 +++++++++++ include/gz/rendering/RenderTypes.hh | 9 + include/gz/rendering/Scene.hh | 28 ++ .../gz/rendering/base/BaseFrustumVisual.hh | 265 ++++++++++++++++ include/gz/rendering/base/BaseScene.hh | 22 ++ .../gz/rendering/ogre/OgreFrustumVisual.hh | 77 +++++ .../gz/rendering/ogre/OgreRenderTypes.hh | 2 + ogre/include/gz/rendering/ogre/OgreScene.hh | 4 + ogre/src/OgreFrustumVisual.cc | 102 ++++++ ogre/src/OgreScene.cc | 10 + .../gz/rendering/ogre2/Ogre2FrustumVisual.hh | 77 +++++ .../gz/rendering/ogre2/Ogre2RenderTypes.hh | 2 + .../include/gz/rendering/ogre2/Ogre2Scene.hh | 4 + ogre2/src/Ogre2FrustumVisual.cc | 290 ++++++++++++++++++ ogre2/src/Ogre2Scene.cc | 10 + src/FrustumVisual.cc | 28 ++ src/base/BaseScene.cc | 31 ++ 17 files changed, 1141 insertions(+) create mode 100644 include/gz/rendering/FrustumVisual.hh create mode 100644 include/gz/rendering/base/BaseFrustumVisual.hh create mode 100644 ogre/include/gz/rendering/ogre/OgreFrustumVisual.hh create mode 100644 ogre/src/OgreFrustumVisual.cc create mode 100644 ogre2/include/gz/rendering/ogre2/Ogre2FrustumVisual.hh create mode 100644 ogre2/src/Ogre2FrustumVisual.cc create mode 100644 src/FrustumVisual.cc diff --git a/include/gz/rendering/FrustumVisual.hh b/include/gz/rendering/FrustumVisual.hh new file mode 100644 index 000000000..bd1771a30 --- /dev/null +++ b/include/gz/rendering/FrustumVisual.hh @@ -0,0 +1,180 @@ +/* + * Copyright (C) 2015 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_RENDERING_FRUSTUMVISUAL_HH_ +#define GZ_RENDERING_FRUSTUMVISUAL_HH_ + +#include +#include +#include +#include +#include +#include "gz/rendering/config.hh" +#include "gz/rendering/Visual.hh" +#include "gz/rendering/Object.hh" +#include "gz/rendering/RenderTypes.hh" +#include "gz/rendering/Marker.hh" + +namespace gz +{ + namespace rendering + { + inline namespace GZ_RENDERING_VERSION_NAMESPACE { + // + /// \brief Planes that define the boundaries of the frustum. + enum GZ_RENDERING_VISIBLE FrustumVisualPlane + { + /// \brief Near plane + FRUSTUM_PLANE_NEAR = 0, + + /// \brief Far plane + FRUSTUM_PLANE_FAR = 1, + + /// \brief Left plane + FRUSTUM_PLANE_LEFT = 2, + + /// \brief Right plane + FRUSTUM_PLANE_RIGHT = 3, + + /// \brief Top plane + FRUSTUM_PLANE_TOP = 4, + + /// \brief Bottom plane + FRUSTUM_PLANE_BOTTOM = 5 + }; + + /// \brief Mathematical representation of a frustum and related functions. + /// This is also known as a view frustum. + class GZ_RENDERING_VISIBLE FrustumVisual : public virtual Visual + { + /// \brief Default constructor. With the following default values: + /// + /// * near: 0.0 + /// * far: 1.0 + /// * fov: 0.78539 radians (45 degrees) + /// * aspect ratio: 1.0 + /// * pose: Pose3d::Zero + protected: FrustumVisual(); + + /// \brief Destructor + public: virtual ~FrustumVisual(); + + /// \brief Constructor + /// \param[in] _near Near plane distance. This is the distance from + /// the frustum's vertex to the closest plane + /// \param[in] _far Far plane distance. This is the distance from the + /// frustum's vertex to the farthest plane. + /// \param[in] _fov Field of view. The field of view is the + /// angle between the frustum's vertex and the edges of the near or far + /// plane. This value represents the horizontal angle. + /// \param[in] _aspectRatio The aspect ratio, which is the width divided + /// by height of the near or far planes. + /// \param[in] _pose Pose of the frustum, which is the vertex (top of + /// the pyramid). + /*protected: FrustumVisual(double _near, + double _far, + const math::Angle &_fov, + double _aspectRatio, + const gz::math::Pose3d &_pose = gz::math::Pose3d::Zero);*/ + + public: virtual void Update() = 0; + + /// \brief Get the near distance. This is the distance from the + /// frustum's vertex to the closest plane. + /// \return Near distance. + /// \sa SetNear + public: virtual double Near() const = 0; + + /// \brief Set the near distance. This is the distance from the + /// frustum's vertex to the closest plane. + /// \param[in] _near Near distance. + /// \sa Near + public: virtual void SetNear(double _near) = 0; + + /// \brief Get the far distance. This is the distance from the + /// frustum's vertex to the farthest plane. + /// \return Far distance. + /// \sa SetFar + public: virtual double Far() const = 0; + + /// \brief Set the far distance. This is the distance from the + /// frustum's vertex to the farthest plane. + /// \param[in] _far Far distance. + /// \sa Far + public: virtual void SetFar(double _far) = 0; + + /// \brief Get the horizontal field of view. The field of view is the + /// angle between the frustum's vertex and the edges of the near or far + /// plane. This value represents the horizontal angle. + /// \return The field of view. + /// \sa SetFOV + public: virtual gz::math::Angle FOV() const = 0; + + /// \brief Set the horizontal field of view. The field of view is the + /// angle between the frustum's vertex and the edges of the near or far + /// plane. This value represents the horizontal angle. + /// \param[in] _fov The field of view. + /// \sa FOV + public: virtual void SetFOV(const gz::math::Angle &_fov) = 0; + + /// \brief Get the aspect ratio, which is the width divided by height + /// of the near or far planes. + /// \return The frustum's aspect ratio. + /// \sa SetAspectRatio + public: virtual double AspectRatio() const = 0; + + /// \brief Set the aspect ratio, which is the width divided by height + /// of the near or far planes. + /// \param[in] _aspectRatio The frustum's aspect ratio. + /// \sa AspectRatio + public: virtual void SetAspectRatio(double _aspectRatio) = 0; + + /// \brief Get a plane of the frustum. + /// \param[in] _plane The plane to return. + /// \return Plane of the frustum. + public: virtual gz::math::Planed Plane(const FrustumVisualPlane _plane) const = 0; + + /// \brief Check if a box lies inside the pyramid frustum. + /// \param[in] _b Box to check. + /// \return True if the box is inside the pyramid frustum. + //public: virtual bool Contains(const gz::math::AxisAlignedBox &_b) const = 0; //TO-DO + + /// \brief Check if a point lies inside the pyramid frustum. + /// \param[in] _p Point to check. + /// \return True if the point is inside the pyramid frustum. + //public: virtual bool Contains(const gz::math::Vector3d &_p) const = 0; //TO-DO + + /// \brief Get the pose of the frustum + /// \return Pose of the frustum + /// \sa SetPose + public: virtual gz::math::Pose3d Pose() const = 0; + + /// \brief Set the pose of the frustum + /// \param[in] _pose Pose of the frustum, top vertex. + /// \sa Pose + public: virtual void SetPose(const gz::math::Pose3d &_pose) = 0; + + /// \brief Compute the planes of the frustum. This is called whenever + /// a property of the frustum is changed. + private: void ComputePlanes(); + + /// \brief Private data pointer + //GZ_UTILS_IMPL_PTR(dataPtr) + }; + } + } +} +#endif diff --git a/include/gz/rendering/RenderTypes.hh b/include/gz/rendering/RenderTypes.hh index 2a7c5e0e8..addac9636 100644 --- a/include/gz/rendering/RenderTypes.hh +++ b/include/gz/rendering/RenderTypes.hh @@ -72,6 +72,7 @@ namespace gz class LightVisual; class JointVisual; class LidarVisual; + class FrustumVisual; class Light; class Marker; class Material; @@ -206,6 +207,10 @@ namespace gz /// \brief Shared pointer to LidarVisual typedef shared_ptr LidarVisualPtr; + /// \typedef FrustumVisualPtr + /// \brief Shared pointer to FrustumVisual + typedef shared_ptr FrustumVisualPtr; + /// \typedef MaterialPtr /// \brief Shared pointer to Material typedef shared_ptr MaterialPtr; @@ -384,6 +389,10 @@ namespace gz /// \brief Shared pointer to const LidarVisual typedef shared_ptr ConstLidarVisualPtr; + /// \typedef const FrustumVisualPtr + /// \brief Shared pointer to const FrustumVisual + typedef shared_ptr ConstFrustumVisualPtr; + /// \typedef const MaterialPtr /// \brief Shared pointer to const Material typedef shared_ptr ConstMaterialPtr; diff --git a/include/gz/rendering/Scene.hh b/include/gz/rendering/Scene.hh index fdaa6436d..bf6b11395 100644 --- a/include/gz/rendering/Scene.hh +++ b/include/gz/rendering/Scene.hh @@ -1108,6 +1108,34 @@ namespace gz public: virtual LidarVisualPtr CreateLidarVisual( unsigned int _id, const std::string &_name) = 0; + /// \brief Create new frusum visual. A unique ID and name will + /// automatically be assigned to the frustum visual. + /// \return The created frustum visual + public: virtual FrustumVisualPtr CreateFrustumVisual() = 0; + + /// \brief Create new frustum visual with the given ID. A unique name + /// will automatically be assigned to the frustum visual. If the given + /// ID is already in use, NULL will be returned. + /// \param[in] _id ID of the new frustum visual + /// \return The created frustum visual + public: virtual FrustumVisualPtr CreateFrustumVisual(unsigned int _id) = 0; + + /// \brief Create new frustum visual with the given name. A unique ID + /// will automatically be assigned to the frustum visual. If the given + /// name is already in use, NULL will be returned. + /// \param[in] _name Name of the new frustum visual + /// \return The created frustum visual + public: virtual FrustumVisualPtr CreateFrustumVisual( + const std::string &_name) = 0; + + /// \brief Create new frustum visual with the given name. If either + /// the given ID or name is already in use, NULL will be returned. + /// \param[in] _id ID of the frustum visual. + /// \param[in] _name Name of the new frustum visual. + /// \return The created frustum visual + public: virtual FrustumVisualPtr CreateFrustumVisual( + unsigned int _id, const std::string &_name) = 0; + /// \brief Create new heightmap geomerty. The rendering::Heightmap will be /// created from the given HeightmapDescriptor. /// \param[in] _desc Data about the heightmap diff --git a/include/gz/rendering/base/BaseFrustumVisual.hh b/include/gz/rendering/base/BaseFrustumVisual.hh new file mode 100644 index 000000000..875156ec4 --- /dev/null +++ b/include/gz/rendering/base/BaseFrustumVisual.hh @@ -0,0 +1,265 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ +#ifndef GZ_RENDERING_BASEFRUSTUMVISUAL_HH_ +#define GZ_RENDERING_BASEFRUSTUMVISUAL_HH_ + +#include + +#include "gz/rendering/FrustumVisual.hh" +#include "gz/rendering/base/BaseObject.hh" +#include "gz/rendering/base/BaseRenderTypes.hh" +#include "gz/rendering/Scene.hh" + +namespace gz +{ + namespace rendering + { + inline namespace GZ_RENDERING_VERSION_NAMESPACE { + /// \brief Base implementation of a Frustum Visual + template + class BaseFrustumVisual : + public virtual FrustumVisual, + public virtual T + { + // Documentation inherited + protected: BaseFrustumVisual(); + + // Documentation inherited + public: virtual ~BaseFrustumVisual(); + + // Documentation inherited + public: virtual void PreRender() override; + + // Documentation inherited + public: virtual void Destroy() override; + + // Documentation inherited + public: virtual void Update() override; + + // Documentation inherited + public: virtual void Init() override; + + // Documentation inherited + public: virtual double Near() const override; + + // Documentation inherited + public: virtual void SetNear(double _near) override; + + // Documentation inherited + public: virtual double Far() const override; + + // Documentation inherited + public: virtual void SetFar(double _far) override; + + // Documentation inherited + public: virtual math::Angle FOV() const override; + + // Documentation inherited + public: virtual void SetFOV(const math::Angle &_fov) override; + + // Documentation inherited + public: virtual double AspectRatio() const override; + + // Documentation inherited + public: virtual void SetAspectRatio(double _aspectRatio) override; + + // Documentation inherited + public: virtual gz::math::Planed Plane(const FrustumVisualPlane _plane) const override; + + // Documentation inherited + //public: virtual bool Contains(const gz::math::AxisAlignedBox &_b) const override; + + // Documentation inherited + //public: virtual bool Contains(const gz::math::Vector3d &_p) const override; + + // Documentation inherited + public: virtual gz::math::Pose3d Pose() const override; + + // Documentation inherited + public: virtual void SetPose(const gz::math::Pose3d &_pose) override; + + /// \brief Create predefined materials for lidar visual + public: virtual void CreateMaterials(); + + /// \brief near value + protected: double near = 0.0; + + /// \brief far value + protected: double far = 1.0; + + /// \brief fov value + protected: gz::math::Angle fov = 0.78539; + + /// \brief aspect ratio value + protected: double aspectRatio = 1.0; + + /// \brief array of plane + protected: std::array planes; + + /// \brief pose of visual + protected: gz::math::Pose3d pose = gz::math::Pose3d::Zero; + }; + + ///////////////////////////////////////////////// + // BaseFrustumVisual + ///////////////////////////////////////////////// + template + BaseFrustumVisual::BaseFrustumVisual() + { + } + + ///////////////////////////////////////////////// + template + BaseFrustumVisual::~BaseFrustumVisual() + { + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::PreRender() + { + T::PreRender(); + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::Destroy() + { + T::Destroy(); + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::Update() + { + // no op + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::Init() + { + T::Init(); + this->CreateMaterials(); + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::SetNear( + double _near) + { + this->near = _near; + } + + ///////////////////////////////////////////////// + template + double BaseFrustumVisual::Near() const + { + return this->near; + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::SetFar( + double _far) + { + this->far = _far; + } + + ///////////////////////////////////////////////// + template + double BaseFrustumVisual::Far() const + { + return this->far; + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::SetFOV( + const gz::math::Angle &_fov) + { + this->fov = _fov; + } + + ///////////////////////////////////////////////// + template + gz::math::Angle BaseFrustumVisual::FOV() const + { + return this->fov; + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::SetAspectRatio( + double _aspectRatio) + { + this->aspectRatio = _aspectRatio; + } + + ///////////////////////////////////////////////// + template + double BaseFrustumVisual::AspectRatio() const + { + return this->aspectRatio; + } + + ///////////////////////////////////////////////// + template + gz::math::Planed BaseFrustumVisual::Plane(const FrustumVisualPlane _plane) const + { + return this->planes[_plane]; + } + + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::SetPose(const gz::math::Pose3d &_pose) + { + this->pose = _pose; + } + + ///////////////////////////////////////////////// + template + gz::math::Pose3d BaseFrustumVisual::Pose() const + { + return this->pose; + } + ///////////////////////////////////////////////// + template + void BaseFrustumVisual::CreateMaterials() + { + MaterialPtr mtl; + + if (!this->Scene()->MaterialRegistered("Frustum/BlueRay")) + { + mtl = this->Scene()->CreateMaterial("Frustum/BlueRay"); + 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.0, 0.0, 1.0); + mtl->SetTransparency(0.0); + mtl->SetCastShadows(false); + mtl->SetReceiveShadows(false); + mtl->SetLightingEnabled(false); + mtl->SetMetalness(0.1f); + mtl->SetReflectivity(0.2); + } + return; + } + } + } +} +#endif diff --git a/include/gz/rendering/base/BaseScene.hh b/include/gz/rendering/base/BaseScene.hh index 200246a2b..b92fd1449 100644 --- a/include/gz/rendering/base/BaseScene.hh +++ b/include/gz/rendering/base/BaseScene.hh @@ -537,6 +537,21 @@ namespace gz public: virtual LidarVisualPtr CreateLidarVisual(unsigned int _id, const std::string &_name) override; + // Documentation inherited. + public: virtual FrustumVisualPtr CreateFrustumVisual() override; + + // Documentation inherited. + public: virtual FrustumVisualPtr CreateFrustumVisual( + unsigned int _id) override; + + // Documentation inherited. + public: virtual FrustumVisualPtr CreateFrustumVisual( + const std::string &_name) override; + + // Documentation inherited. + public: virtual FrustumVisualPtr CreateFrustumVisual(unsigned int _id, + const std::string &_name) override; + // Documentation inherited. public: virtual HeightmapPtr CreateHeightmap( const HeightmapDescriptor &_desc) override; @@ -828,6 +843,13 @@ namespace gz protected: virtual LidarVisualPtr CreateLidarVisualImpl(unsigned int _id, const std::string &_name) = 0; + /// \brief Implementation for creating a frustum visual + /// \param[in] _id unique object id. + /// \param[in] _name unique object name. + /// \return Pointer to a frustum visual + protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(unsigned int _id, + const std::string &_name) = 0; + /// \brief Implementation for creating a heightmap geometry /// \param[in] _id Unique object id. /// \param[in] _name Unique object name. diff --git a/ogre/include/gz/rendering/ogre/OgreFrustumVisual.hh b/ogre/include/gz/rendering/ogre/OgreFrustumVisual.hh new file mode 100644 index 000000000..ede578b37 --- /dev/null +++ b/ogre/include/gz/rendering/ogre/OgreFrustumVisual.hh @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef GZ_RENDERING_OGRE_OGREFRUSTUMVISUAL_HH_ +#define GZ_RENDERING_OGRE_OGREFRUSTUMVISUAL_HH_ + +#include +#include +#include "gz/rendering/base/BaseFrustumVisual.hh" +#include "gz/rendering/ogre/OgreVisual.hh" +#include "gz/rendering/ogre/OgreIncludes.hh" +#include "gz/rendering/ogre/OgreScene.hh" + +namespace gz +{ + namespace rendering + { + inline namespace GZ_RENDERING_VERSION_NAMESPACE { + // + // Forward declaration + class OgreFrustumVisualPrivate; + + /// \brief Ogre implementation of a Frustum Visual. + class GZ_RENDERING_OGRE_VISIBLE OgreFrustumVisual + : public BaseFrustumVisual + { + /// \brief Constructor + protected: OgreFrustumVisual(); + + /// \brief Destructor + public: virtual ~OgreFrustumVisual(); + + // Documentation inherited. + public: virtual void Init() override; + + // Documentation inherited. + public: virtual void PreRender() override; + + // Documentation inherited. + public: virtual void Destroy() override; + + // Documentation inherited + public: virtual void Update() override; + + /// \brief Create the Frustum Visual in ogre + private: void Create(); + + /// \brief Clear data stored by dynamiclines + private: void ClearVisualData(); + + // Documentation inherited + public: virtual void SetVisible(bool _visible) override; + + /// \brief Frustum Visual should only be created by scene. + private: friend class OgreScene; + + /// \brief Private data class + private: std::unique_ptr dataPtr; + }; + } + } +} +#endif diff --git a/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh b/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh index 06fabd6f8..031caa34d 100644 --- a/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh +++ b/ogre/include/gz/rendering/ogre/OgreRenderTypes.hh @@ -33,6 +33,7 @@ namespace gz class OgreCOMVisual; class OgreDepthCamera; class OgreDirectionalLight; + class OgreFrustumVisual; class OgreGeometry; class OgreGizmoVisual; class OgreGpuRays; @@ -86,6 +87,7 @@ namespace gz typedef shared_ptr OgreCOMVisualPtr; typedef shared_ptr OgreDepthCameraPtr; typedef shared_ptr OgreDirectionalLightPtr; + typedef shared_ptr OgreFrustumVisualPtr; typedef shared_ptr OgreGeometryPtr; typedef shared_ptr OgreGeometryStorePtr; typedef shared_ptr OgreGizmoVisualPtr; diff --git a/ogre/include/gz/rendering/ogre/OgreScene.hh b/ogre/include/gz/rendering/ogre/OgreScene.hh index a55c8de66..19f14f368 100644 --- a/ogre/include/gz/rendering/ogre/OgreScene.hh +++ b/ogre/include/gz/rendering/ogre/OgreScene.hh @@ -180,6 +180,10 @@ namespace gz protected: virtual LidarVisualPtr CreateLidarVisualImpl(unsigned int _id, const std::string &_name) override; + // Documentation inherited + protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(unsigned int _id, + const std::string &_name) override; + // Documentation inherited protected: virtual WireBoxPtr CreateWireBoxImpl(unsigned int _id, const std::string &_name) override; diff --git a/ogre/src/OgreFrustumVisual.cc b/ogre/src/OgreFrustumVisual.cc new file mode 100644 index 000000000..abe7c1b79 --- /dev/null +++ b/ogre/src/OgreFrustumVisual.cc @@ -0,0 +1,102 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include "gz/rendering/ogre/OgreDynamicLines.hh" +#include "gz/rendering/ogre/OgreFrustumVisual.hh" +#include "gz/rendering/ogre/OgreScene.hh" +#include "gz/rendering/ogre/OgreMarker.hh" +#include "gz/rendering/ogre/OgreGeometry.hh" + + +class gz::rendering::OgreFrustumVisualPrivate +{ + /// \brief Frustum Ray DynamicLines Object to display + public: std::vector> rayLines; + + /// \brief Frustum visual type + //public: FrustumVisualPlane frustumVisPlane = + //FrustumVisualPlane::FRUSTUM_PLANE_TOP; + + /// \brief The visibility of the visual + public: bool visible = true; + + /// \brief Each corner of the frustum. + public: std::array points; + + /// \brief each edge of the frustum. + public: std::array, 12> edges; +}; + +using namespace gz; +using namespace rendering; + +////////////////////////////////////////////////// +OgreFrustumVisual::OgreFrustumVisual() + : dataPtr(new OgreFrustumVisualPrivate) +{ +} + +////////////////////////////////////////////////// +OgreFrustumVisual::~OgreFrustumVisual() +{ + // no ops +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::PreRender() +{ + // no ops +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::Destroy() +{ + BaseFrustumVisual::Destroy(); +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::Init() +{ + BaseFrustumVisual::Init(); + this->Create(); +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::Create() +{ + // no ops +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::ClearVisualData() +{ + this->dataPtr->rayLines.clear(); +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::Update() +{ + //no ops FIX-ME +} + +////////////////////////////////////////////////// +void OgreFrustumVisual::SetVisible(bool _visible) +{ + this->dataPtr->visible = _visible; + this->ogreNode->setVisible(this->dataPtr->visible); +} diff --git a/ogre/src/OgreScene.cc b/ogre/src/OgreScene.cc index 36531eb21..981c64fe4 100644 --- a/ogre/src/OgreScene.cc +++ b/ogre/src/OgreScene.cc @@ -35,6 +35,7 @@ #include "gz/rendering/ogre/OgreInertiaVisual.hh" #include "gz/rendering/ogre/OgreJointVisual.hh" #include "gz/rendering/ogre/OgreLidarVisual.hh" +#include "gz/rendering/ogre/OgreFrustumVisual.hh" #include "gz/rendering/ogre/OgreLightVisual.hh" #include "gz/rendering/ogre/OgreMarker.hh" #include "gz/rendering/ogre/OgreMaterial.hh" @@ -622,6 +623,15 @@ LidarVisualPtr OgreScene::CreateLidarVisualImpl(unsigned int _id, return (result) ? lidar: nullptr; } +////////////////////////////////////////////////// +FrustumVisualPtr OgreScene::CreateFrustumVisualImpl(unsigned int _id, + const std::string &_name) +{ + OgreFrustumVisualPtr frustum(new OgreFrustumVisual); + bool result = this->InitObject(frustum, _id, _name); + return (result) ? frustum: nullptr; +} + ////////////////////////////////////////////////// TextPtr OgreScene::CreateTextImpl(unsigned int _id, const std::string &_name) { diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2FrustumVisual.hh b/ogre2/include/gz/rendering/ogre2/Ogre2FrustumVisual.hh new file mode 100644 index 000000000..f0c63cec0 --- /dev/null +++ b/ogre2/include/gz/rendering/ogre2/Ogre2FrustumVisual.hh @@ -0,0 +1,77 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#ifndef GZ_RENDERING_OGRE2_OGREFRUSTUMVISUAL_HH_ +#define GZ_RENDERING_OGRE2_OGREFRUSTUMVISUAL_HH_ + +#include +#include +#include "gz/rendering/base/BaseFrustumVisual.hh" +#include "gz/rendering/ogre2/Ogre2Visual.hh" +#include "gz/rendering/ogre2/Ogre2Includes.hh" +#include "gz/rendering/ogre2/Ogre2Scene.hh" + +namespace gz +{ + namespace rendering + { + inline namespace GZ_RENDERING_VERSION_NAMESPACE { + // + // Forward declaration + class Ogre2FrustumVisualPrivate; + + /// \brief Ogre 2.x implementation of a Frustum Visual. + class GZ_RENDERING_OGRE2_VISIBLE Ogre2FrustumVisual + : public BaseFrustumVisual + { + /// \brief Constructor + protected: Ogre2FrustumVisual(); + + /// \brief Destructor + public: virtual ~Ogre2FrustumVisual(); + + // Documentation inherited. + public: virtual void Init() override; + + // Documentation inherited. + public: virtual void PreRender() override; + + // Documentation inherited. + public: virtual void Destroy() override; + + // Documentation inherited + public: virtual void Update() override; + + /// \brief Create the Frustum Visual in ogre + private: void Create(); + + /// \brief Clear data stored by dynamiclines + private: void ClearVisualData(); + + // Documentation inherited + public: virtual void SetVisible(bool _visible) override; + + /// \brief Frustum Visual should only be created by scene. + private: friend class Ogre2Scene; + + /// \brief Private data class + private: std::unique_ptr dataPtr; + }; + } + } +} +#endif diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh index b2c0fd6dd..d8c5ef4eb 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2RenderTypes.hh @@ -36,6 +36,7 @@ namespace gz class Ogre2COMVisual; class Ogre2DepthCamera; class Ogre2DirectionalLight; + class Ogre2FrustumVisual; class Ogre2Geometry; class Ogre2GizmoVisual; class Ogre2GlobalIlluminationCiVct; @@ -92,6 +93,7 @@ namespace gz typedef shared_ptr Ogre2COMVisualPtr; typedef shared_ptr Ogre2DepthCameraPtr; typedef shared_ptr Ogre2DirectionalLightPtr; + typedef shared_ptr Ogre2FrustumVisualPtr; typedef shared_ptr Ogre2GeometryPtr; typedef shared_ptr Ogre2GizmoVisualPtr; typedef shared_ptr Ogre2GpuRaysPtr; diff --git a/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh b/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh index 323c2b30b..4c2e5d1ef 100644 --- a/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh +++ b/ogre2/include/gz/rendering/ogre2/Ogre2Scene.hh @@ -343,6 +343,10 @@ namespace gz protected: virtual LidarVisualPtr CreateLidarVisualImpl(unsigned int _id, const std::string &_name) override; + // Documentation inherited + protected: virtual FrustumVisualPtr CreateFrustumVisualImpl(unsigned int _id, + const std::string &_name) override; + // Documentation inherited protected: virtual WireBoxPtr CreateWireBoxImpl(unsigned int _id, const std::string &_name) override; diff --git a/ogre2/src/Ogre2FrustumVisual.cc b/ogre2/src/Ogre2FrustumVisual.cc new file mode 100644 index 000000000..7669bcd8f --- /dev/null +++ b/ogre2/src/Ogre2FrustumVisual.cc @@ -0,0 +1,290 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifdef __APPLE__ + #define GL_SILENCE_DEPRECATION + #include + #include +#else +#ifndef _WIN32 + #include +#endif +#endif + +#include + +#include "gz/rendering/ogre2/Ogre2Conversions.hh" +#include "gz/rendering/ogre2/Ogre2DynamicRenderable.hh" +#include "gz/rendering/ogre2/Ogre2FrustumVisual.hh" +#include "gz/rendering/ogre2/Ogre2RenderEngine.hh" +#include "gz/rendering/ogre2/Ogre2Scene.hh" +#include "gz/rendering/ogre2/Ogre2Marker.hh" +#include "gz/rendering/ogre2/Ogre2Geometry.hh" + +#ifdef _MSC_VER + #pragma warning(push, 0) +#endif +#include +#include +#include +#include +#include +#ifdef _MSC_VER + #pragma warning(pop) +#endif + +class gz::rendering::Ogre2FrustumVisualPrivate +{ + /// \brief Frustum Ray DynamicLines Object to display + public: std::vector> rayLines; + + /// \brief Frustum visual type + //public: FrustumVisualPlane frustumVisPlane = + //FrustumVisualPlane::FRUSTUM_PLANE_TOP; + + /// \brief The visibility of the visual + public: bool visible = true; + + /// \brief Each corner of the frustum. + public: std::array points; + + /// \brief each edge of the frustum. + public: std::array, 12> edges; +}; + +using namespace gz; +using namespace rendering; + +////////////////////////////////////////////////// +Ogre2FrustumVisual::Ogre2FrustumVisual() + : dataPtr(new Ogre2FrustumVisualPrivate) +{ +} + +////////////////////////////////////////////////// +Ogre2FrustumVisual::~Ogre2FrustumVisual() +{ + // no ops +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::PreRender() +{ + // no ops +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::Destroy() +{ + BaseFrustumVisual::Destroy(); +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::Init() +{ + BaseFrustumVisual::Init(); + this->Create(); +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::Create() +{ + // enable GL_PROGRAM_POINT_SIZE so we can set gl_PointSize in vertex shader + auto engine = Ogre2RenderEngine::Instance(); + std::string renderSystemName = + engine->OgreRoot()->getRenderSystem()->getFriendlyName(); + if (renderSystemName.find("OpenGL") != std::string::npos) + { +#ifdef __APPLE__ + glEnable(GL_VERTEX_PROGRAM_POINT_SIZE); +#else +#ifndef _WIN32 + glEnable(GL_PROGRAM_POINT_SIZE); +#endif +#endif + } +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::ClearVisualData() +{ + this->dataPtr->rayLines.clear(); +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::Update() +{ + std::shared_ptr renderable = + std::shared_ptr( + new Ogre2DynamicRenderable(this->Scene())); + this->ogreNode->attachObject(renderable->OgreObject()); + + #if (!(OGRE_VERSION <= ((1 << 16) | (10 << 8) | 7))) + // the Materials are assigned here to avoid repetitive search for materials + Ogre::MaterialPtr rayLineMat = + Ogre::MaterialManager::getSingleton().getByName( + "Frustum/BlueRay"); + #endif + + #if (OGRE_VERSION <= ((1 << 16) | (10 << 8) | 7)) + MaterialPtr mat = this->Scene()->Material("Frustum/BlueRay"); + #else + //MaterialPtr mat = this->Scene()->Material(rayLineMat); //FIX-ME + MaterialPtr mat = this->Scene()->Material("Frustum/BlueRay"); + #endif + + renderable->SetMaterial(mat, false); + renderable->SetOperationType(MT_LINE_LIST); + this->dataPtr->rayLines.push_back(renderable); + + // Tangent of half the field of view. + double tanFOV2 = std::tan(this->fov() * 0.5); + + // Width of near plane + double nearWidth = 2.0 * tanFOV2 * this->near; + + // Height of near plane + double nearHeight = nearWidth / this->aspectRatio; + + // Width of far plane + double farWidth = 2.0 * tanFOV2 * this->far; + + // Height of far plane + double farHeight = farWidth / this->aspectRatio; + + // Up, right, and forward unit vectors. + gz::math::Vector3d forward = this->pose.Rot().RotateVector(gz::math::Vector3d::UnitX); + gz::math::Vector3d up = this->pose.Rot().RotateVector(gz::math::Vector3d::UnitZ); + gz::math::Vector3d right = this->pose.Rot().RotateVector(-gz::math::Vector3d::UnitY); + + // Near plane center + gz::math::Vector3d nearCenter = this->pose.Pos() + forward * this->near; + + // Far plane center + gz::math::Vector3d farCenter = this->pose.Pos() + forward * this->far; + + // These four variables are here for convenience. + gz::math::Vector3d upNearHeight2 = up * (nearHeight * 0.5); + gz::math::Vector3d rightNearWidth2 = right * (nearWidth * 0.5); + gz::math::Vector3d upFarHeight2 = up * (farHeight * 0.5); + gz::math::Vector3d rightFarWidth2 = right * (farWidth * 0.5); + + // Compute the vertices of the near plane + gz::math::Vector3d nearTopLeft = nearCenter + upNearHeight2 - rightNearWidth2; + gz::math::Vector3d nearTopRight = nearCenter + upNearHeight2 + rightNearWidth2; + gz::math::Vector3d nearBottomLeft = nearCenter - upNearHeight2 - rightNearWidth2; + gz::math::Vector3d nearBottomRight = nearCenter - upNearHeight2 + rightNearWidth2; + + // Compute the vertices of the far plane + gz::math::Vector3d farTopLeft = farCenter + upFarHeight2 - rightFarWidth2; + gz::math::Vector3d farTopRight = farCenter + upFarHeight2 + rightFarWidth2; + gz::math::Vector3d farBottomLeft = farCenter - upFarHeight2 - rightFarWidth2; + gz::math::Vector3d farBottomRight = farCenter - upFarHeight2 + rightFarWidth2; + + // Save these vertices + this->dataPtr->points[0] = nearTopLeft; + this->dataPtr->points[1] = nearTopRight; + this->dataPtr->points[2] = nearBottomLeft; + this->dataPtr->points[3] = nearBottomRight; + this->dataPtr->points[4] = farTopLeft; + this->dataPtr->points[5] = farTopRight; + this->dataPtr->points[6] = farBottomLeft; + this->dataPtr->points[7] = farBottomRight; + + // Save the edges + this->dataPtr->edges[0] = {nearTopLeft, nearTopRight}; + this->dataPtr->edges[1] = {nearTopLeft, nearBottomLeft}; + this->dataPtr->edges[2] = {nearTopLeft, farTopLeft}; + this->dataPtr->edges[3] = {nearTopRight, nearBottomRight}; + this->dataPtr->edges[4] = {nearTopRight, farTopRight}; + this->dataPtr->edges[5] = {nearBottomLeft, nearBottomRight}; + this->dataPtr->edges[6] = {nearBottomLeft, farBottomLeft}; + this->dataPtr->edges[7] = {farTopLeft, farTopRight}; + this->dataPtr->edges[8] = {farTopLeft, farBottomLeft}; + this->dataPtr->edges[9] = {farTopRight, farBottomRight}; + this->dataPtr->edges[10] = {farBottomLeft, farBottomRight}; + this->dataPtr->edges[11] = {farBottomRight, nearBottomRight}; + + gz::math::Vector3d leftCenter = + (farTopLeft + nearTopLeft + farBottomLeft + nearBottomLeft) / 4.0; + + gz::math::Vector3d rightCenter = + (farTopRight + nearTopRight + farBottomRight + nearBottomRight) / 4.0; + + gz::math::Vector3d topCenter = + (farTopRight + nearTopRight + farTopLeft + nearTopLeft) / 4.0; + + gz::math::Vector3d bottomCenter = + (farBottomRight + nearBottomRight + farBottomLeft + nearBottomLeft) / 4.0; + + // For creating the frustum visuals + renderable->AddPoint(gz::math::Vector3d(this->near, nearWidth, nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, nearWidth, -nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, nearWidth, -nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, -nearWidth, -nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, -nearWidth, -nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, -nearWidth, nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, -nearWidth, nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, nearWidth, nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, farWidth, farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, farWidth, -farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, farWidth, -farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, -farWidth, -farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, -farWidth, -farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, -farWidth, farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, -farWidth, farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, farWidth, farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, nearWidth, nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, farWidth, farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, -nearWidth, nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, -farWidth, farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, -nearWidth, -nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, -farWidth, -farHeight)); + renderable->AddPoint(gz::math::Vector3d(this->near, nearWidth, -nearHeight)); + renderable->AddPoint(gz::math::Vector3d(this->far, farWidth, -farHeight)); + + // Compute plane offsets + // Set the planes, where the first value is the plane normal and the + // second the plane offset + gz::math::Vector3d norm = gz::math::Vector3d::Normal(nearTopLeft, nearTopRight, nearBottomLeft); + this->planes[FrustumVisualPlane::FRUSTUM_PLANE_NEAR].Set(norm, nearCenter.Dot(norm)); + + norm = gz::math::Vector3d::Normal(farTopRight, farTopLeft, farBottomLeft); + this->planes[FrustumVisualPlane::FRUSTUM_PLANE_FAR].Set(norm, farCenter.Dot(norm)); + + norm = gz::math::Vector3d::Normal(farTopLeft, nearTopLeft, nearBottomLeft); + this->planes[FrustumVisualPlane::FRUSTUM_PLANE_LEFT].Set(norm, leftCenter.Dot(norm)); + + norm = gz::math::Vector3d::Normal(nearTopRight, farTopRight, farBottomRight); + this->planes[FrustumVisualPlane::FRUSTUM_PLANE_RIGHT].Set(norm, rightCenter.Dot(norm)); + + norm = gz::math::Vector3d::Normal(nearTopLeft, farTopLeft, nearTopRight); + this->planes[FrustumVisualPlane::FRUSTUM_PLANE_TOP].Set(norm, topCenter.Dot(norm)); + + norm = gz::math::Vector3d::Normal(nearBottomLeft, nearBottomRight, farBottomRight); + this->planes[FrustumVisualPlane::FRUSTUM_PLANE_BOTTOM].Set(norm, bottomCenter.Dot(norm)); + + renderable->Update(); + this->SetVisible(this->dataPtr->visible); +} + +////////////////////////////////////////////////// +void Ogre2FrustumVisual::SetVisible(bool _visible) +{ + this->dataPtr->visible = _visible; + this->ogreNode->setVisible(this->dataPtr->visible); +} diff --git a/ogre2/src/Ogre2Scene.cc b/ogre2/src/Ogre2Scene.cc index 2d164e235..22d172593 100644 --- a/ogre2/src/Ogre2Scene.cc +++ b/ogre2/src/Ogre2Scene.cc @@ -53,6 +53,7 @@ #include "gz/rendering/ogre2/Ogre2Light.hh" #include "gz/rendering/ogre2/Ogre2LightVisual.hh" #include "gz/rendering/ogre2/Ogre2LidarVisual.hh" +#include "gz/rendering/ogre2/Ogre2FrustumVisual.hh" #include "gz/rendering/ogre2/Ogre2Marker.hh" #include "gz/rendering/ogre2/Ogre2Material.hh" #include "gz/rendering/ogre2/Ogre2MeshFactory.hh" @@ -1344,6 +1345,15 @@ LidarVisualPtr Ogre2Scene::CreateLidarVisualImpl(unsigned int _id, return (result) ? lidar: nullptr; } +////////////////////////////////////////////////// +FrustumVisualPtr Ogre2Scene::CreateFrustumVisualImpl(unsigned int _id, + const std::string &_name) +{ + Ogre2FrustumVisualPtr frustum(new Ogre2FrustumVisual); + bool result = this->InitObject(frustum, _id, _name); + return (result) ? frustum: nullptr; +} + ////////////////////////////////////////////////// TextPtr Ogre2Scene::CreateTextImpl(unsigned int /*_id*/, const std::string &/*_name*/) diff --git a/src/FrustumVisual.cc b/src/FrustumVisual.cc new file mode 100644 index 000000000..a1021142f --- /dev/null +++ b/src/FrustumVisual.cc @@ -0,0 +1,28 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + + +#include "gz/rendering/FrustumVisual.hh" + +using namespace gz; +using namespace rendering; + +////////////////////////////////////////////////// +FrustumVisual::FrustumVisual() = default; + +////////////////////////////////////////////////// +FrustumVisual::~FrustumVisual() = default; diff --git a/src/base/BaseScene.cc b/src/base/BaseScene.cc index b65112fb3..2a03743c7 100644 --- a/src/base/BaseScene.cc +++ b/src/base/BaseScene.cc @@ -30,6 +30,7 @@ #include "gz/rendering/InstallationDirectories.hh" #include "gz/rendering/JointVisual.hh" #include "gz/rendering/LidarVisual.hh" +#include "gz/rendering/FrustumVisual.hh" #include "gz/rendering/LightVisual.hh" #include "gz/rendering/Camera.hh" #include "gz/rendering/Capsule.hh" @@ -1262,6 +1263,36 @@ LidarVisualPtr BaseScene::CreateLidarVisual(unsigned int _id, return (result) ? lidar : nullptr; } +////////////////////////////////////////////////// +FrustumVisualPtr BaseScene::CreateFrustumVisual() +{ + unsigned int objId = this->CreateObjectId(); + return this->CreateFrustumVisual(objId); +} + +////////////////////////////////////////////////// +FrustumVisualPtr BaseScene::CreateFrustumVisual(unsigned int _id) +{ + const std::string objName = this->CreateObjectName(_id, "FrustumVisual"); + return this->CreateFrustumVisual(_id, objName); +} + +////////////////////////////////////////////////// +FrustumVisualPtr BaseScene::CreateFrustumVisual(const std::string &_name) +{ + unsigned int objId = this->CreateObjectId(); + return this->CreateFrustumVisual(objId, _name); +} + +////////////////////////////////////////////////// +FrustumVisualPtr BaseScene::CreateFrustumVisual(unsigned int _id, + const std::string &_name) +{ + FrustumVisualPtr frustum = this->CreateFrustumVisualImpl(_id, _name); + bool result = this->RegisterVisual(frustum); + return (result) ? frustum : nullptr; +} + ////////////////////////////////////////////////// WireBoxPtr BaseScene::CreateWireBox() {