Skip to content

Commit

Permalink
Clone visuals and geometries (#397)
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <[email protected]>
Signed-off-by: Ian Chen <[email protected]>

Co-authored-by: Ian Chen <[email protected]>
  • Loading branch information
adlarkin and iche033 authored Sep 22, 2021
1 parent 064bdf5 commit 5bf8dc6
Show file tree
Hide file tree
Showing 18 changed files with 480 additions and 10 deletions.
5 changes: 5 additions & 0 deletions include/ignition/rendering/Geometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#define IGNITION_RENDERING_GEOMETRY_HH_

#include <string>

#include "ignition/rendering/config.hh"
#include "ignition/rendering/RenderTypes.hh"
#include "ignition/rendering/Object.hh"
Expand Down Expand Up @@ -66,6 +67,10 @@ namespace ignition
/// \brief Get the material of this geometry
/// \return Material used by this geometry
public: virtual MaterialPtr Material() const = 0;

/// \brief Clone the geometry.
/// \return The cloned geometry.
public: virtual GeometryPtr Clone() const = 0;
};
}
}
Expand Down
9 changes: 9 additions & 0 deletions include/ignition/rendering/Mesh.hh
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <ignition/math/Matrix4.hh>
#include "ignition/rendering/config.hh"
#include "ignition/rendering/Geometry.hh"
#include "ignition/rendering/MeshDescriptor.hh"
#include "ignition/rendering/Object.hh"

namespace ignition
Expand Down Expand Up @@ -119,6 +120,14 @@ namespace ignition
/// \return The sub-mesh at the given index
public: virtual SubMeshPtr SubMeshByIndex(
unsigned int _index) const = 0;

/// \brief Set the mesh's mesh descriptor
/// \return The mesh's mesh descriptor
public: virtual void SetDescriptor(const MeshDescriptor &_desc) = 0;

/// \brief Get the mesh's mesh descriptor
/// \return The mesh's mesh descriptor
public: virtual const MeshDescriptor &Descriptor() const = 0;
};

/// \class SubMesh Mesh.hh ignition/rendering/Mesh.hh
Expand Down
11 changes: 10 additions & 1 deletion include/ignition/rendering/Visual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ namespace ignition
/// \return the Pointer to the material assigned to this visual. If the
/// material is cloned at the time it is set to this visual, the cloned
/// material will be returned.
public: virtual MaterialPtr Material() = 0;
public: virtual MaterialPtr Material() const = 0;

/// \brief Enable or disable wireframe
/// \param[in] _show True to enable wireframe
Expand Down Expand Up @@ -142,6 +142,15 @@ namespace ignition
/// \return The local bounding box
public: virtual ignition::math::AxisAlignedBox LocalBoundingBox()
const = 0;

/// \brief Clone the visual (and its children) with a new name.
/// \param[in] _name Name of the cloned Visual. Set this to an empty
/// string to auto-generate a unique name for the cloned visual.
/// \param[in] _newParent Parent of the cloned Visual. Set to nullptr if
/// the cloned visual should have no parent.
/// \return The visual. nullptr is returned if cloning failed.
public: virtual VisualPtr Clone(const std::string &_name,
NodePtr _newParent) const = 0;
};
}
}
Expand Down
30 changes: 30 additions & 0 deletions include/ignition/rendering/base/BaseCapsule.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,10 @@
#ifndef IGNITION_RENDERING_BASECAPSULE_HH_
#define IGNITION_RENDERING_BASECAPSULE_HH_

#include <ignition/common/Console.hh>

#include "ignition/rendering/Capsule.hh"
#include "ignition/rendering/Scene.hh"
#include "ignition/rendering/base/BaseObject.hh"

namespace ignition
Expand Down Expand Up @@ -50,6 +53,9 @@ namespace ignition
// Documentation inherited
public: virtual double Length() const override;

// Documentation inherited
public: virtual GeometryPtr Clone() const override;

/// \brief Radius of the capsule
protected: double radius = 0.5;

Expand Down Expand Up @@ -103,6 +109,30 @@ namespace ignition
{
return this->length;
}

/////////////////////////////////////////////////
template <class T>
GeometryPtr BaseCapsule<T>::Clone() const
{
if (!this->Scene())
{
ignerr << "Cloning a Capsule failed because the capsule to be "
<< "cloned does not belong to a scene.\n";
return nullptr;
}

auto result = this->Scene()->CreateCapsule();
if (result)
{
result->SetRadius(this->Radius());
result->SetLength(this->Length());

if (this->Material())
result->SetMaterial(this->Material());
}

return result;
}
}
}
}
Expand Down
14 changes: 14 additions & 0 deletions include/ignition/rendering/base/BaseGeometry.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@
#define IGNITION_RENDERING_BASE_BASEGEOMETRY_HH_

#include <string>

#include <ignition/common/Console.hh>

#include "ignition/rendering/Geometry.hh"
#include "ignition/rendering/Scene.hh"

Expand Down Expand Up @@ -48,6 +51,9 @@ namespace ignition
public: virtual void SetMaterial(MaterialPtr _material,
bool _unique = true) override = 0;

// Documentation inherited
public: virtual GeometryPtr Clone() const override;

// Documentation inherited
public: virtual void Destroy() override;
};
Expand Down Expand Up @@ -89,6 +95,14 @@ namespace ignition
if (material) this->SetMaterial(material, _unique);
}

//////////////////////////////////////////////////
template <class T>
GeometryPtr BaseGeometry<T>::Clone() const
{
ignwarn << "Clone functionality for Geometry does not exist yet.\n";
return nullptr;
}

//////////////////////////////////////////////////
template <class T>
void BaseGeometry<T>::Destroy()
Expand Down
68 changes: 68 additions & 0 deletions include/ignition/rendering/base/BaseMesh.hh
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,15 @@ namespace ignition

public: virtual void PreRender() override;

// Documentation inherited.
public: virtual GeometryPtr Clone() const override;

// Documentation inherited.
public: void SetDescriptor(const MeshDescriptor &_desc) override;

// Documentation inherited.
public: const MeshDescriptor &Descriptor() const override;

// Documentation inherited
public: virtual void Destroy() override;

Expand All @@ -111,6 +120,9 @@ namespace ignition

/// \brief Pointer to currently assigned material
protected: MaterialPtr material;

/// \brief MeshDescriptor for this mesh
protected: MeshDescriptor meshDescriptor;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -315,6 +327,61 @@ namespace ignition
T::PreRender();
}

//////////////////////////////////////////////////
template <class T>
GeometryPtr BaseMesh<T>::Clone() const
{
if (!this->Scene())
{
ignerr << "Cloning a mesh failed because the mesh to be "
<< "cloned does not belong to a scene.\n";
return nullptr;
}
else if (this->meshDescriptor.meshName.empty())
{
ignerr << "Cloning a geometry failed because the name of the mesh is "
<< "missing.\n";
return nullptr;
}

auto result = this->Scene()->CreateMesh(this->meshDescriptor);
if (result)
{
if (this->Material())
{
// this call will set the material for the mesh and its submeshes
result->SetMaterial(this->Material());
}
else
{
// if the mesh doesn't have a material, clone any existing submesh
// materials
for (unsigned int i = 0; i < this->SubMeshCount(); ++i)
{
auto existingSubMeshMaterial = this->SubMeshByIndex(i)->Material();
if (existingSubMeshMaterial)
result->SubMeshByIndex(i)->SetMaterial(existingSubMeshMaterial);
}
}
}

return result;
}

//////////////////////////////////////////////////
template <class T>
const MeshDescriptor &BaseMesh<T>::Descriptor() const
{
return this->meshDescriptor;
}

//////////////////////////////////////////////////
template <class T>
void BaseMesh<T>::SetDescriptor(const MeshDescriptor &_desc)
{
this->meshDescriptor = _desc;
}

//////////////////////////////////////////////////
template <class T>
void BaseMesh<T>::Destroy()
Expand All @@ -324,6 +391,7 @@ namespace ignition
if (this->material && this->ownsMaterial)
this->Scene()->DestroyMaterial(this->material);
this->material.reset();
this->meshDescriptor = MeshDescriptor();
}

//////////////////////////////////////////////////
Expand Down
76 changes: 74 additions & 2 deletions include/ignition/rendering/base/BaseVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ namespace ignition
bool _unique = true) override;

// Documentation inherited.
public: virtual MaterialPtr Material() override;
public: virtual MaterialPtr Material() const override;

// Documentation inherited.
public: virtual void SetWireframe(bool _show) override;
Expand Down Expand Up @@ -114,6 +114,10 @@ namespace ignition
public: virtual ignition::math::AxisAlignedBox LocalBoundingBox()
const override;

// Documentation inherited.
public: virtual VisualPtr Clone(const std::string &_name,
NodePtr _newParent) const override;

protected: virtual void PreRenderChildren() override;

protected: virtual void PreRenderGeometries();
Expand Down Expand Up @@ -293,7 +297,7 @@ namespace ignition

//////////////////////////////////////////////////
template <class T>
MaterialPtr BaseVisual<T>::Material()
MaterialPtr BaseVisual<T>::Material() const
{
return this->material;
}
Expand Down Expand Up @@ -471,6 +475,74 @@ namespace ignition
{
return this->visibilityFlags;
}

//////////////////////////////////////////////////
template <class T>
VisualPtr BaseVisual<T>::Clone(const std::string &_name,
NodePtr _newParent) const
{
ScenePtr scene_ = this->Scene();
if (nullptr == scene_)
{
ignerr << "Cloning a visual failed because the visual to be cloned is "
<< "not attached to a scene.\n";
return nullptr;
}
VisualPtr result;
if (_name.empty())
result = scene_->CreateVisual();
else
result = scene_->CreateVisual(_name);

if (nullptr != _newParent)
{
auto parentScene = _newParent->Scene();
if (nullptr != parentScene && parentScene->Id() != scene_->Id())
{
ignerr << "Cloning a visual failed because the desired parent of the "
<< "cloned visual belongs to a different scene.\n";
scene_->DestroyVisual(result);
return nullptr;
}
_newParent->AddChild(result);
}

result->SetOrigin(this->Origin());
result->SetInheritScale(this->InheritScale());
result->SetLocalScale(this->LocalScale());
result->SetLocalPose(this->LocalPose());
result->SetVisibilityFlags(this->VisibilityFlags());
result->SetWireframe(this->Wireframe());

// if the visual that was cloned has child visuals, clone those as well
auto children_ =
std::dynamic_pointer_cast<BaseStore<ignition::rendering::Node, T>>(
this->Children());
if (!children_)
{
ignerr << "Cast failed in BaseVisual::Clone\n";
scene_->DestroyVisual(result);
return nullptr;
}
for (auto it = children_->Begin(); it != children_->End(); ++it)
{
NodePtr child = it->second;
VisualPtr visual = std::dynamic_pointer_cast<Visual>(child);
if (nullptr != visual)
visual->Clone("", result);
}

for (unsigned int i = 0; i < this->GeometryCount(); ++i)
result->AddGeometry(this->GeometryByIndex(i)->Clone());

if (this->Material())
result->SetMaterial(this->Material());

for (const auto &[key, val] : this->userData)
result->SetUserData(key, val);

return result;
}
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion ogre/include/ignition/rendering/ogre/OgreCOMVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ namespace ignition
public: virtual VisualPtr SphereVisual() const override;

// Documentation inherited.
public: virtual MaterialPtr Material() const;
public: virtual MaterialPtr Material() const override;

// Documentation inherited.
public: virtual void SetMaterial(
Expand Down
2 changes: 1 addition & 1 deletion ogre/include/ignition/rendering/ogre/OgreInertiaVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ namespace ignition
public: VisualPtr BoxVisual() const override;

// Documentation inherited.
public: virtual MaterialPtr Material() const;
public: virtual MaterialPtr Material() const override;

// Documentation inherited.
public: virtual void SetMaterial(
Expand Down
2 changes: 1 addition & 1 deletion ogre/include/ignition/rendering/ogre/OgreLightVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ namespace ignition
public: void CreateVisual();

// Documentation inherited.
public: virtual MaterialPtr Material() const;
public: virtual MaterialPtr Material() const override;

// Documentation inherited.
public: virtual void SetMaterial(
Expand Down
1 change: 1 addition & 0 deletions ogre/src/OgreScene.cc
Original file line number Diff line number Diff line change
Expand Up @@ -546,6 +546,7 @@ MeshPtr OgreScene::CreateMeshImpl(unsigned int _id, const std::string &_name,
if (nullptr == mesh)
return nullptr;

mesh->SetDescriptor(_desc);
bool result = this->InitObject(mesh, _id, _name);
return (result) ? mesh : nullptr;
}
Expand Down
2 changes: 1 addition & 1 deletion ogre2/include/ignition/rendering/ogre2/Ogre2COMVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ namespace ignition
public: virtual VisualPtr SphereVisual() const override;

// Documentation inherited.
public: virtual MaterialPtr Material() const;
public: virtual MaterialPtr Material() const override;

// Documentation inherited.
public: virtual void SetMaterial(
Expand Down
Loading

0 comments on commit 5bf8dc6

Please sign in to comment.