Skip to content

Commit

Permalink
UserData methods moved from Visual to Node (#358)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Jul 15, 2021
1 parent 8081b8f commit f3f75a5
Show file tree
Hide file tree
Showing 4 changed files with 45 additions and 45 deletions.
17 changes: 17 additions & 0 deletions include/ignition/rendering/Node.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,10 @@
#ifndef IGNITION_RENDERING_NODE_HH_
#define IGNITION_RENDERING_NODE_HH_

#include <map>
#include <string>
#include <variant>

#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>

Expand All @@ -32,6 +35,9 @@ namespace ignition
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
//
using Variant =
std::variant<int, float, double, std::string, bool, unsigned int>;

/// \class Node Node.hh ignition/rendering/Node.hh
/// \brief Represents a single posable node in the scene graph
class IGNITION_RENDERING_VISIBLE Node :
Expand Down Expand Up @@ -302,6 +308,17 @@ namespace ignition
/// \brief Remove all child nodes from this node
/// This detaches all the child nodes but does not destroy them
public: virtual void RemoveChildren() = 0;

/// \brief Store any custom data associated with this visual
/// \param[in] _key Unique key
/// \param[in] _value Value in any type
public: virtual void SetUserData(
const std::string &_key, Variant _value) = 0;

/// \brief Get custom data stored in this visual
/// \param[in] _key Unique key
/// \return Value in any type
public: virtual Variant UserData(const std::string &_key) const = 0;
};
}
}
Expand Down
15 changes: 0 additions & 15 deletions include/ignition/rendering/Visual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#ifndef IGNITION_RENDERING_VISUAL_HH_
#define IGNITION_RENDERING_VISUAL_HH_

#include <variant>
#include <string>
#include <ignition/math/AxisAlignedBox.hh>
#include "ignition/rendering/config.hh"
Expand All @@ -28,9 +27,6 @@ namespace ignition
namespace rendering
{
inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
//
using Variant = std::variant<int, float, double, std::string>;

/// \class Visual Visual.hh ignition/rendering/Visual.hh
/// \brief Represents a visual node in a scene graph. A Visual is the only
/// node that can have Geometry and other Visual children.
Expand Down Expand Up @@ -138,17 +134,6 @@ namespace ignition
/// \param[in] _visibility flags
public: virtual void RemoveVisibilityFlags(uint32_t _flags) = 0;

/// \brief Store any custom data associated with this visual
/// \param[in] _key Unique key
/// \param[in] _value Value in any type
public: virtual void SetUserData(const std::string &_key,
Variant _value) = 0;

/// \brief Get custom data stored in this visual
/// \param[in] _key Unique key
/// \param[in] _value Value in any type
public: virtual Variant UserData(const std::string &_key) const = 0;

/// \brief Get the bounding box in world frame coordinates.
/// \return The axis aligned bounding box
public: virtual ignition::math::AxisAlignedBox BoundingBox() const = 0;
Expand Down
30 changes: 28 additions & 2 deletions include/ignition/rendering/base/BaseNode.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,9 @@
#ifndef IGNITION_RENDERING_BASE_BASENODE_HH_
#define IGNITION_RENDERING_BASE_BASENODE_HH_

#include <map>
#include <string>

#include "ignition/rendering/Node.hh"
#include "ignition/rendering/Storage.hh"
#include "ignition/rendering/base/BaseStorage.hh"
Expand Down Expand Up @@ -168,6 +170,13 @@ namespace ignition

public: virtual void PreRender() override;

// Documentation inherited
public: virtual void SetUserData(const std::string &_key, Variant _value)
override;

// Documentation inherited
public: virtual Variant UserData(const std::string &_key) const override;

protected: virtual void PreRenderChildren();

protected: virtual math::Pose3d RawLocalPose() const = 0;
Expand All @@ -186,6 +195,9 @@ namespace ignition
const math::Vector3d &_scale) = 0;

protected: math::Vector3d origin;

/// \brief A map of custom key value data
protected: std::map<std::string, Variant> userData;
};

//////////////////////////////////////////////////
Expand Down Expand Up @@ -572,8 +584,6 @@ namespace ignition
this->SetLocalScale(_scale * this->LocalScale());
}



//////////////////////////////////////////////////
template <class T>
void BaseNode<T>::Destroy()
Expand Down Expand Up @@ -631,6 +641,22 @@ namespace ignition
return this->Children()->GetByIndex(_index);
}
}

template <class T>
void BaseNode<T>::SetUserData(const std::string &_key, Variant _value)
{
this->userData[_key] = _value;
}

template <class T>
Variant BaseNode<T>::UserData(const std::string &_key) const
{
Variant value;
auto it = this->userData.find(_key);
if (it != this->userData.end())
value = it->second;
return value;
}
}
}
#endif
28 changes: 0 additions & 28 deletions include/ignition/rendering/base/BaseVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -106,13 +106,6 @@ namespace ignition
// Documentation inherited
public: virtual void Destroy() override;

// Documentation inherited.
public: virtual void SetUserData(const std::string &_key,
Variant _value) override;

// Documentation inherited.
public: virtual Variant UserData(const std::string &_key) const override;

// Documentation inherited.
public: virtual ignition::math::AxisAlignedBox BoundingBox()
const override;
Expand All @@ -134,9 +127,6 @@ namespace ignition
/// \brief Pointer to material assigned to this visual
protected: MaterialPtr material;

/// \brief A map of custom key value data
protected: std::map<std::string, Variant> userData;

/// \brief Visual's visibility flags
protected: uint32_t visibilityFlags = IGN_VISIBILITY_ALL;

Expand Down Expand Up @@ -481,24 +471,6 @@ namespace ignition
{
return this->visibilityFlags;
}

//////////////////////////////////////////////////
template <class T>
void BaseVisual<T>::SetUserData(const std::string &_key, Variant _value)
{
this->userData[_key] = _value;
}

//////////////////////////////////////////////////
template <class T>
Variant BaseVisual<T>::UserData(const std::string &_key) const
{
Variant value;
auto it = this->userData.find(_key);
if (it != this->userData.end())
value = it->second;
return value;
}
}
}
}
Expand Down

0 comments on commit f3f75a5

Please sign in to comment.