diff --git a/examples/tutorials/nb_python/ECCV_2020_Advanced_Features.py b/examples/tutorials/nb_python/ECCV_2020_Advanced_Features.py index e2b04a58b8..cff7459bd1 100644 --- a/examples/tutorials/nb_python/ECCV_2020_Advanced_Features.py +++ b/examples/tutorials/nb_python/ECCV_2020_Advanced_Features.py @@ -171,7 +171,11 @@ def build_dict_of_PhyObj_attrs(phys_obj_template): False, "boolean", ) - res_dict["is_dirty"] = (phys_obj_template.is_dirty, False, "boolean") + res_dict["filenames_are_dirty"] = ( + phys_obj_template.filenames_are_dirty, + False, + "boolean", + ) return res_dict diff --git a/examples/tutorials/nb_python/asset_viewer.py b/examples/tutorials/nb_python/asset_viewer.py index 800996632a..fc7aacb6fa 100644 --- a/examples/tutorials/nb_python/asset_viewer.py +++ b/examples/tutorials/nb_python/asset_viewer.py @@ -331,7 +331,11 @@ def build_dict_of_PhyObj_attrs(phys_obj_template): "boolean", ) res_dict["is_collidable"] = (phys_obj_template.is_collidable, True, "boolean") - res_dict["is_dirty"] = (phys_obj_template.is_dirty, False, "boolean") + res_dict["filenames_are_dirty"] = ( + phys_obj_template.filenames_are_dirty, + False, + "boolean", + ) return res_dict diff --git a/examples/tutorials/notebooks/ECCV_2020_Advanced_Features.ipynb b/examples/tutorials/notebooks/ECCV_2020_Advanced_Features.ipynb index ba236a60b4..4c70621a03 100644 --- a/examples/tutorials/notebooks/ECCV_2020_Advanced_Features.ipynb +++ b/examples/tutorials/notebooks/ECCV_2020_Advanced_Features.ipynb @@ -163,7 +163,11 @@ " False,\n", " \"boolean\",\n", " )\n", - " res_dict[\"is_dirty\"] = (phys_obj_template.is_dirty, False, \"boolean\")\n", + " res_dict[\"filenames_are_dirty\"] = (\n", + " phys_obj_template.filenames_are_dirty,\n", + " False,\n", + " \"boolean\",\n", + " )\n", " return res_dict\n", "\n", "\n", diff --git a/examples/tutorials/notebooks/asset_viewer.ipynb b/examples/tutorials/notebooks/asset_viewer.ipynb index 1d7e244125..b482cf35f0 100644 --- a/examples/tutorials/notebooks/asset_viewer.ipynb +++ b/examples/tutorials/notebooks/asset_viewer.ipynb @@ -329,7 +329,11 @@ " \"boolean\",\n", " )\n", " res_dict[\"is_collidable\"] = (phys_obj_template.is_collidable, True, \"boolean\")\n", - " res_dict[\"is_dirty\"] = (phys_obj_template.is_dirty, False, \"boolean\")\n", + " res_dict[\"filenames_are_dirty\"] = (\n", + " phys_obj_template.filenames_are_dirty,\n", + " False,\n", + " \"boolean\",\n", + " )\n", " return res_dict\n", "\n", "\n", diff --git a/src/esp/assets/ResourceManager.cpp b/src/esp/assets/ResourceManager.cpp index 3227d510b6..f0ad6df3fd 100644 --- a/src/esp/assets/ResourceManager.cpp +++ b/src/esp/assets/ResourceManager.cpp @@ -2885,7 +2885,7 @@ bool ResourceManager::instantiateAssetsOnDemand( // object has acquired a copy of its parent attributes. No object should // ever have a copy of attributes with isDirty == true - any editing of // attributes for objects requires object rebuilding. - if (objectAttributes->getIsDirty()) { + if (objectAttributes->getFilePathsAreDirty()) { CORRADE_ASSERT( (getObjectAttributesManager()->registerObject( objectAttributes, objectTemplateHandle) != ID_UNDEFINED), diff --git a/src/esp/bindings/AttributesBindings.cpp b/src/esp/bindings/AttributesBindings.cpp index e086ea896c..47e9e876f6 100644 --- a/src/esp/bindings/AttributesBindings.cpp +++ b/src/esp/bindings/AttributesBindings.cpp @@ -453,7 +453,11 @@ void initAttributesBindings(py::module& m) { R"(Class name of Attributes template.)") .def_property_readonly( "csv_info", &AbstractAttributes::getObjectInfo, - R"(Comma-separated informational string describing this Attributes template)"); + R"(Comma-separated informational string describing this Attributes template)") + .def_property_readonly( + "filenames_are_dirty", &AbstractAttributes::getFilePathsAreDirty, + R"(Whether filenames or paths in this attributes have been changed requiring + re-registration before they can be used to create an object. )"); // Attributes should only use named properties or subconfigurations to set // specific values, to guarantee essential value type integrity. This will @@ -680,11 +684,7 @@ void initAttributesBindings(py::module& m) { .def_property( "is_collidable", &ObjectAttributes::getIsCollidable, &ObjectAttributes::setIsCollidable, - R"(Whether constructions built from this template are collidable upon initialization.)") - .def_property_readonly( - "is_dirty", &AbstractObjectAttributes::getIsDirty, - R"(Whether values in this attributes have been changed requiring - re-registration before they can be used to create an object. )"); + R"(Whether constructions built from this template are collidable upon initialization.)"); // ==== ObjectAttributes ==== py::class_( diff --git a/src/esp/bindings/ConfigBindings.cpp b/src/esp/bindings/ConfigBindings.cpp index 78425448e8..c2a4db78f0 100644 --- a/src/esp/bindings/ConfigBindings.cpp +++ b/src/esp/bindings/ConfigBindings.cpp @@ -152,7 +152,7 @@ void initConfigBindings(py::module& m) { R"(Returns whether or not this Configuration has the passed key. Does not check subconfigurations.)", "key"_a) .def( - "has_key_to_type", &Configuration::hasKeyOfType, + "has_key_to_type", &Configuration::hasKeyToValOfType, R"(Returns whether passed key points to a value of specified ConfigValType)", "key"_a, "value_type"_a) .def( diff --git a/src/esp/bindings/SimBindings.cpp b/src/esp/bindings/SimBindings.cpp index 41e990e57b..4e2600047c 100644 --- a/src/esp/bindings/SimBindings.cpp +++ b/src/esp/bindings/SimBindings.cpp @@ -164,7 +164,7 @@ void initSimBindings(py::module& m) { R"(Use gfx_replay_manager for replay recording and playback.)") .def("seed", &Simulator::seed, "new_seed"_a) .def("reconfigure", &Simulator::reconfigure, "configuration"_a) - .def("reset", &Simulator::reset) + .def("reset", [](Simulator& self) { self.reset(false); }) .def( "close", &Simulator::close, "destroy"_a = true, R"(Free all loaded assets and GPU contexts. Use destroy=true except where noted in tutorials/async_rendering.py.)") diff --git a/src/esp/core/Configuration.cpp b/src/esp/core/Configuration.cpp index b95b1f735d..d5992aafba 100644 --- a/src/esp/core/Configuration.cpp +++ b/src/esp/core/Configuration.cpp @@ -207,18 +207,35 @@ bool operator==(const ConfigValue& a, const ConfigValue& b) { if (a._typeAndFlags != b._typeAndFlags) { return false; } + const auto dataType = a.getType(); // Pointer-backed data types need to have _data dereffed - if (isConfigValTypePointerBased(a.getType())) { - return pointerBasedConfigTypeHandlerFor(a.getType()) - .comparator(a._data, b._data); + if (isConfigValTypePointerBased(dataType)) { + return pointerBasedConfigTypeHandlerFor(dataType).comparator(a._data, + b._data); } - // Trivial type : a._data holds the actual value - // _data array will always hold only legal data, since a ConfigValue should - // never change type. + // By here we know the type is a trivial type and that the types for both + // values are equal + if (a.reqsFuzzyCompare()) { + // Type is specified to require fuzzy comparison + switch (dataType) { + case ConfigValType::Double: { + return Mn::Math::equal(a.get(), b.get()); + } + default: { + CORRADE_ASSERT_UNREACHABLE( + "Unknown/unsupported Type in ConfigValue::operator==()", ""); + } + } + } + + // Trivial non-fuzzy-comparison-requiring type : a._data holds the actual + // value _data array will always hold only legal data, since a ConfigValue + // should never change type. return std::equal(std::begin(a._data), std::end(a._data), std::begin(b._data)); -} + +} // ConfigValue::operator== bool operator!=(const ConfigValue& a, const ConfigValue& b) { return !(a == b); @@ -236,7 +253,7 @@ std::string ConfigValue::getAsString() const { return std::to_string(get()); } case ConfigValType::Double: { - return std::to_string(get()); + return Cr::Utility::formatString("{}", get()); } case ConfigValType::String: { return get(); @@ -295,7 +312,8 @@ std::string ConfigValue::getAsString() const { io::JsonGenericValue ConfigValue::writeToJsonObject( io::JsonAllocator& allocator) const { - // unknown is checked before this function is called, so does not need support + // unknown is checked before this function is called, so does not need + // support switch (getType()) { case ConfigValType::Boolean: { return io::toJsonValue(get(), allocator); @@ -487,8 +505,8 @@ int Configuration::loadOneConfigFromJson(int numConfigSettings, } else { // The array does not match any currently supported magnum // objects, so place in indexed subconfig of values. - // decrement count by 1 - the recursive subgroup load will count all the - // values. + // decrement count by 1 - the recursive subgroup load will count all + // the values. --numConfigSettings; // create a new subgroup std::shared_ptr subGroupPtr = @@ -496,8 +514,8 @@ int Configuration::loadOneConfigFromJson(int numConfigSettings, // load array into subconfig numConfigSettings += subGroupPtr->loadFromJsonArray(jsonObj); } - // value in array is a number of specified length, else it is a string, an - // object or a nested array + // value in array is a number of specified length, else it is a string, + // an object or a nested array } else { // decrement count by 1 - the recursive subgroup load will count all the // values. @@ -584,8 +602,8 @@ void Configuration::writeValuesToJson(io::JsonGenericValue& jsonObj, << "`, so nothing will be written to JSON for this key."; } else if (valIter->second.shouldWriteToFile()) { - // Create Generic value for key, using allocator, to make sure its a copy - // and lives long enough + // Create Generic value for key, using allocator, to make sure its a + // copy and lives long enough writeValueToJsonInternal(valIter->second, valIter->first.c_str(), jsonObj, allocator); } else { @@ -602,8 +620,8 @@ void Configuration::writeSubconfigsToJson(io::JsonGenericValue& jsonObj, ++cfgIter) { // only save if subconfig tree has value entries if (cfgIter->second->getConfigTreeNumValues() > 0) { - // Create Generic value for key, using allocator, to make sure its a copy - // and lives long enough + // Create Generic value for key, using allocator, to make sure its a + // copy and lives long enough io::JsonGenericValue name{cfgIter->first.c_str(), allocator}; io::JsonGenericValue subObj = cfgIter->second->writeToJsonObject(allocator); @@ -663,9 +681,9 @@ void Configuration::setSubconfigValsOfTypeInVector( /** * @brief Retrieves a shared pointer to a copy of the subConfig @ref * esp::core::config::Configuration that has the passed @p name . This will - * create a pointer to a new sub-configuration if none exists already with that - * name, but will not add this configuration to this Configuration's internal - * storage. + * create a pointer to a new sub-configuration if none exists already with + * that name, but will not add this configuration to this Configuration's + * internal storage. * * @param name The name of the configuration to retrieve. * @return A pointer to a copy of the configuration having the requested @@ -783,6 +801,52 @@ std::vector Configuration::findValue( return breadcrumbs; } +void Configuration::overwriteWithConfig( + const std::shared_ptr& src) { + if (src->getNumEntries() == 0) { + return; + } + // copy every element over from src + for (const auto& elem : src->valueMap_) { + valueMap_[elem.first] = elem.second; + } + // merge subconfigs + for (const auto& subConfig : src->configMap_) { + const auto name = subConfig.first; + // make if DNE and merge src subconfig + addOrEditSubgroup(name).first->second->overwriteWithConfig( + subConfig.second); + } +} // Configuration::overwriteWithConfig + +void Configuration::filterFromConfig( + const std::shared_ptr& src) { + if (src->getNumEntries() == 0) { + return; + } + // filter out every element that is present with the same value in both src + // and this. + for (const auto& elem : src->valueMap_) { + ValueMapType::const_iterator mapIter = valueMap_.find(elem.first); + // if present and has the same data, erase this configuration's data + if ((mapIter != valueMap_.end()) && (mapIter->second == elem.second)) { + valueMap_.erase(mapIter); + } + } + // repeat process on all subconfigs of src that are present in this. + for (const auto& subConfig : src->configMap_) { + // find if this has subconfig of same name + ConfigMapType::iterator mapIter = configMap_.find(subConfig.first); + if (mapIter != configMap_.end()) { + mapIter->second->filterFromConfig(subConfig.second); + // remove the subconfig if it has no entries after filtering + if (mapIter->second->getNumEntries() == 0) { + configMap_.erase(mapIter); + } + } + } +} // Configuration::filterFromConfig + Configuration& Configuration::operator=(const Configuration& otr) { if (this != &otr) { configMap_.clear(); @@ -820,7 +884,7 @@ Mn::Debug& operator<<(Mn::Debug& debug, const Configuration& cfg) { bool operator==(const Configuration& a, const Configuration& b) { if ((a.getNumSubconfigs() != b.getNumSubconfigs()) || - (a.getNumValues() != b.getNumValues())) { + (a.getNumVisibleValues() != b.getNumVisibleValues())) { return false; } for (const auto& entry : a.configMap_) { diff --git a/src/esp/core/Configuration.h b/src/esp/core/Configuration.h index e5234109a2..6844144b62 100644 --- a/src/esp/core/Configuration.h +++ b/src/esp/core/Configuration.h @@ -133,6 +133,13 @@ enum ConfigValStatus : uint64_t { * properly read from or written to file otherwise. */ isTranslated = 1ULL << 34, + + /** + * @brief This @ref ConfigValue requires manual fuzzy comparison (i.e. floating + * point scalar type) using the Magnum::Math::equal method. Magnum types + * already perform fuzzy comparison. + */ + reqsFuzzyComparison = 1ULL << 35, }; // enum class ConfigValStatus /** @@ -157,6 +164,24 @@ constexpr bool isConfigValTypeNonTrivial(ConfigValType type) { static_cast(ConfigValType::_nonTrivialTypes); } +/** + * @brief Function template to return whether the value requires fuzzy + * comparison or not. + */ +template +constexpr bool useFuzzyComparisonFor() { + // Default for all types is no. + return false; +} + +/** + * @brief Specify that @ref ConfigValType::Double scalar floating point values require fuzzy comparison + */ +template <> +constexpr bool useFuzzyComparisonFor() { + return true; +} + /** * @brief Function template to return type enum for specified type. All * supported types should have a specialization of this function handling their @@ -272,8 +297,7 @@ constexpr ConfigValType configValTypeFor() { /** * @brief Stream operator to support display of @ref ConfigValType enum tags */ -MAGNUM_EXPORT Mn::Debug& operator<<(Mn::Debug& debug, - const ConfigValType& value); +Mn::Debug& operator<<(Mn::Debug& debug, const ConfigValType& value); /** * @brief This class uses an anonymous tagged union to store values of different @@ -355,7 +379,8 @@ class ConfigValue { } /** - * @brief Get this ConfigVal's value. Type is stored as a Pointer. + * @brief Get this ConfigVal's value. For Types that are stored in _data as a + * Pointer. */ template EnableIf()), const T&> @@ -367,7 +392,8 @@ class ConfigValue { } /** - * @brief Get this ConfigVal's value. Type is stored directly in buffer. + * @brief Get this ConfigVal's value. For Types that are stored directly in + * buffer. */ template EnableIf()), const T&> @@ -413,6 +439,9 @@ class ConfigValue { //_data should be destructed at this point, construct a new value setInternalTyped(value); + // set whether this type requires fuzzy comparison or not + setReqsFuzzyCompare(useFuzzyComparisonFor()); + } // ConfigValue::setInternal /** @@ -621,6 +650,29 @@ class ConfigValue { setState(ConfigValStatus::isTranslated, isTranslated); } + /** + * @brief Check whether this ConfigVal requires a fuzzy comparison for + * equality (i.e. for a scalar double). + * + * The comparisons for such a type + * should use Magnum::Math::equal to be consistent with similarly configured + * magnum types. + */ + inline bool reqsFuzzyCompare() const { + return getState(ConfigValStatus::reqsFuzzyComparison); + } + /** + * @brief Check whether this ConfigVal requires a fuzzy comparison for + * equality (i.e. for a scalar double). + * + * The comparisons for such a type + * should use Magnum::Math::equal to be consistent with similarly configured + * magnum types. + */ + inline void setReqsFuzzyCompare(bool fuzzyCompare) { + setState(ConfigValStatus::reqsFuzzyComparison, fuzzyCompare); + } + /** * @brief Whether or not this @ref ConfigValue should be written to file during * common execution. The reason we may not want to do this might be that the @@ -657,7 +709,7 @@ class ConfigValue { /** * @brief provide debug stream support for @ref ConfigValue */ -MAGNUM_EXPORT Mn::Debug& operator<<(Mn::Debug& debug, const ConfigValue& value); +Mn::Debug& operator<<(Mn::Debug& debug, const ConfigValue& value); /** * @brief This class holds Configuration data in a map of ConfigValues, and @@ -697,7 +749,7 @@ class Configuration { : configMap_(std::move(otr.configMap_)), valueMap_(std::move(otr.valueMap_)) {} // move ctor - // virtual destructor set to that pybind11 recognizes attributes inheritance + // virtual destructor set so that pybind11 recognizes attributes inheritance // from Configuration to be polymorphic virtual ~Configuration() = default; @@ -751,6 +803,8 @@ class Configuration { return {}; } + // ****************** Value Status ****************** + /** * @brief Return the @ref ConfigValType enum representing the type of the * value referenced by the passed @p key or @ref ConfigValType::Unknown @@ -765,6 +819,46 @@ class Configuration { return ConfigValType::Unknown; } + /** + * @brief Returns whether or not the @ref ConfigValue specified + * by @p key is a default/initialization value or was intentionally set. + */ + bool isDefaultVal(const std::string& key) const { + ValueMapType::const_iterator mapIter = valueMap_.find(key); + if (mapIter != valueMap_.end()) { + return mapIter->second.isDefaultVal(); + } + ESP_ERROR() << "Key :" << key << "not present in Configuration."; + return false; + } + + /** + * @brief Returns whether or not the @ref ConfigValue specified + * by @p key is a hidden value intended to be be only used internally. + */ + bool isHiddenVal(const std::string& key) const { + ValueMapType::const_iterator mapIter = valueMap_.find(key); + if (mapIter != valueMap_.end()) { + return mapIter->second.isHiddenVal(); + } + ESP_ERROR() << "Key :" << key << "not present in Configuration."; + return false; + } + + /** + * @brief Returns whether or not the @ref ConfigValue specified + * by @p key is a translated value, meaning a string that corresponds to, and + * is translated into, an enum value for consumption. + */ + bool isTranslated(const std::string& key) const { + ValueMapType::const_iterator mapIter = valueMap_.find(key); + if (mapIter != valueMap_.end()) { + return mapIter->second.isTranslated(); + } + ESP_ERROR() << "Key :" << key << "not present in Configuration."; + return false; + } + // ****************** String Conversion ****************** /** @@ -1133,10 +1227,26 @@ class Configuration { } /** - * @brief returns number of values in this Configuration. + * @brief Returns number of values in this Configuration. */ int getNumValues() const { return valueMap_.size(); } + /** + * @brief Returns number of non-hidden values in this Configuration. This is + * necessary for determining whether or not configurations are "effectively" + * equal, where they contain the same data but may vary in number + * internal-use-only fields. + */ + int getNumVisibleValues() const { + int numVals = 0; + for (const auto& val : valueMap_) { + if (!val.second.isHiddenVal()) { + numVals += 1; + } + } + return numVals; + } + /** * @brief Return total number of values held by this Configuration and all * its subconfigs. @@ -1163,7 +1273,8 @@ class Configuration { * @param desiredType the @ref ConfigValType to compare the value's type to * @return Whether @p key references a value that is of @p desiredType. */ - bool hasKeyOfType(const std::string& key, ConfigValType desiredType) { + bool hasKeyToValOfType(const std::string& key, + ConfigValType desiredType) const { ValueMapType::const_iterator mapIter = valueMap_.find(key); return (mapIter != valueMap_.end() && (mapIter->second.getType() == desiredType)); @@ -1247,7 +1358,6 @@ class Configuration { * @return A pointer to a copy of the Configuration having the requested * name, cast to the appropriate type, or nullptr if not found. */ - template std::shared_ptr getSubconfigCopy(const std::string& cfgName) const { static_assert(std::is_base_of::value, @@ -1371,27 +1481,24 @@ class Configuration { /** * @brief Merges Configuration pointed to by @p src into this - * Configuration, including all subconfigs. Passed config overwrites + * Configuration, including all subconfigs. Passed config overwrites * existing data in this config. * @param src The source of Configuration data we wish to merge into this * Configuration. */ - void overwriteWithConfig(const std::shared_ptr& src) { - if (src->getNumEntries() == 0) { - return; - } - // copy every element over from src - for (const auto& elem : src->valueMap_) { - valueMap_[elem.first] = elem.second; - } - // merge subconfigs - for (const auto& subConfig : src->configMap_) { - const auto name = subConfig.first; - // make if DNE and merge src subconfig - addOrEditSubgroup(name).first->second->overwriteWithConfig( - subConfig.second); - } - } + void overwriteWithConfig(const std::shared_ptr& src); + + /** + * @brief Performs the opposite operation to @ref Configuration::overwriteWithConfig. + * All values and subconfigs in the passed Configuration will be removed from + * this config unless the data they hold is different. Any empty subconfigs + * will be removed as well. + * + * @param src The source of Configuration data we wish to prune from this + * Configuration. + */ + + void filterFromConfig(const std::shared_ptr& src); /** * @brief Returns a const iterator across the map of values. @@ -1695,8 +1802,7 @@ class Configuration { /** * @brief provide debug stream support for a @ref Configuration */ -MAGNUM_EXPORT Mn::Debug& operator<<(Mn::Debug& debug, - const Configuration& value); +Mn::Debug& operator<<(Mn::Debug& debug, const Configuration& value); template <> std::vector Configuration::getSubconfigValsOfTypeInVector( diff --git a/src/esp/core/Esp.h b/src/esp/core/Esp.h index 537e90c2cc..934372933a 100644 --- a/src/esp/core/Esp.h +++ b/src/esp/core/Esp.h @@ -98,6 +98,9 @@ constexpr int ID_UNDEFINED = -1; /** @brief Object ID of the rigid stage.*/ constexpr int RIGID_STAGE_ID = 0; +/** @brief Link ID of the baseLink for articulated objects */ +constexpr int BASELINK_ID = -1; + static const double NO_TIME = 0.0; /** diff --git a/src/esp/core/managedContainers/AbstractFileBasedManagedObject.h b/src/esp/core/managedContainers/AbstractFileBasedManagedObject.h index 402d8ee8ac..49d23239c6 100644 --- a/src/esp/core/managedContainers/AbstractFileBasedManagedObject.h +++ b/src/esp/core/managedContainers/AbstractFileBasedManagedObject.h @@ -42,6 +42,26 @@ class AbstractFileBasedManagedObject : public AbstractManagedObject { */ virtual std::string getActualFilename() const = 0; + /** + * @brief Get whether this ManagedObject has been saved to disk in its current + * state. Only applicable to registered ManagedObjects + */ + virtual bool isAttrSaved() const = 0; + + /** + * @brief Set that this ManagedObject has values that are different than its + * most recently saved-to-disk version. This is called when the ManagedObject + * is registered. + */ + + void setAttrIsNotSaved() { setFileSaveStatus(false); } + + /** + * @brief Set that this ManagedObject is the same as its saved-to-disk + * version. This is called when the ManagedObject is saved to disk. + */ + void setAttrIsSaved() { setFileSaveStatus(true); } + /** * @brief This will return a simplified version of the * AbstractFileBasedManagedObject handle, removing extensions and any parent @@ -66,6 +86,13 @@ class AbstractFileBasedManagedObject : public AbstractManagedObject { virtual io::JsonGenericValue writeToJsonObject( io::JsonAllocator& allocator) const = 0; + protected: + /** + * @brief Set this ManagedObject's save status (i.e. whether it matches its + * version on disk or not) + */ + virtual void setFileSaveStatus(bool _isSaved) = 0; + public: ESP_SMART_POINTERS(AbstractFileBasedManagedObject) }; // class AbstractFileBasedManagedObject diff --git a/src/esp/core/managedContainers/ManagedContainer.h b/src/esp/core/managedContainers/ManagedContainer.h index dd4590c011..4654c7939e 100644 --- a/src/esp/core/managedContainers/ManagedContainer.h +++ b/src/esp/core/managedContainers/ManagedContainer.h @@ -163,11 +163,10 @@ class ManagedContainer : public ManagedContainerBase { "registration, so registration aborted."; return ID_UNDEFINED; } - if ("" != objectHandle) { - return this->registerObjectInternal(std::move(managedObject), - objectHandle, forceRegistration); - } - std::string handleToSet = managedObject->getHandle(); + // If no handle give, query object for handle + std::string handleToSet = + ("" == objectHandle) ? managedObject->getHandle() : objectHandle; + // if still no handle, fail registration if ("" == handleToSet) { ESP_ERROR(Magnum::Debug::Flag::NoSpace) << "<" << this->objectType_ @@ -175,6 +174,7 @@ class ManagedContainer : public ManagedContainerBase { "so registration aborted."; return ID_UNDEFINED; } + // Perform actual registration return this->registerObjectInternal(std::move(managedObject), handleToSet, forceRegistration); } // ManagedContainer::registerObject @@ -193,8 +193,7 @@ class ManagedContainer : public ManagedContainerBase { */ ManagedPtr getObjectByID(int managedObjectID) const { std::string objectHandle = getObjectHandleByID(managedObjectID); - if (!checkExistsWithMessage(objectHandle, - "<" + this->objectType_ + ">::getObjectByID")) { + if (!checkExistsWithMessage(objectHandle, "getObjectByID")) { return nullptr; } return getObjectInternal(objectHandle); @@ -212,8 +211,7 @@ class ManagedContainer : public ManagedContainerBase { * exist */ ManagedPtr getObjectByHandle(const std::string& objectHandle) const { - if (!checkExistsWithMessage( - objectHandle, "<" + this->objectType_ + ">::getObjectByHandle")) { + if (!checkExistsWithMessage(objectHandle, "getObjectByHandle")) { return nullptr; } return getObjectInternal(objectHandle); @@ -250,7 +248,7 @@ class ManagedContainer : public ManagedContainerBase { /** * @brief Retrieve a map of key= std::string handle; value = copy of * ManagedPtr object where the handles match the passed @p . See @ref - * ManagedContainerBase::getObjectHandlesBySubStringPerType. + * ManagedContainerBase::getAllObjectHandlesBySubStringPerType. * @param subStr substring key to search for within existing managed objects. * @param contains whether to search for keys containing, or excluding, * passed @p subStr @@ -260,8 +258,8 @@ class ManagedContainer : public ManagedContainerBase { std::unordered_map getObjectsByHandleSubstring( const std::string& subStr = "", bool contains = true) { - std::vector keys = this->getObjectHandlesBySubStringPerType( - objectLibKeyByID_, subStr, contains, false); + std::vector keys = + this->getAllObjectHandlesBySubStringPerType(subStr, contains, false); std::unordered_map res; res.reserve(keys.size()); @@ -280,7 +278,7 @@ class ManagedContainer : public ManagedContainerBase { /** * @brief Templated version. Retrieve a map of key= std::string handle; value * = copy of ManagedPtr object where the handles match the passed @p . See - * @ref ManagedContainerBase::getObjectHandlesBySubStringPerType. + * @ref ManagedContainerBase::getAllObjectHandlesBySubStringPerType. * * @tparam Desired downcast class that inerheits from this ManagedContainer's * ManagedObject type. @@ -294,8 +292,11 @@ class ManagedContainer : public ManagedContainerBase { std::unordered_map> getObjectsByHandleSubstring(const std::string& subStr = "", bool contains = true) { - std::vector keys = this->getObjectHandlesBySubStringPerType( - objectLibKeyByID_, subStr, contains, false); + static_assert(std::is_base_of::value, + "ManagedContainer :: Desired type must be derived from " + "Managed object type"); + std::vector keys = + this->getAllObjectHandlesBySubStringPerType(subStr, contains, false); std::unordered_map> res; res.reserve(keys.size()); @@ -321,13 +322,10 @@ class ManagedContainer : public ManagedContainerBase { */ ManagedPtr removeObjectByID(int objectID) { std::string objectHandle = getObjectHandleByID(objectID); - if (!checkExistsWithMessage( - objectHandle, "<" + this->objectType_ + ">::removeObjectByID")) { + if (!checkExistsWithMessage(objectHandle, "removeObjectByID")) { return nullptr; } - return removeObjectInternal( - objectID, objectHandle, - "<" + this->objectType_ + ">::removeObjectByID"); + return removeObjectInternal(objectID, objectHandle, "removeObjectByID"); } /** @@ -339,17 +337,14 @@ class ManagedContainer : public ManagedContainerBase { * exist */ ManagedPtr removeObjectByHandle(const std::string& objectHandle) { - if (!checkExistsWithMessage(objectHandle, "<" + this->objectType_ + - ">::removeObjectByHandle")) { + if (!checkExistsWithMessage(objectHandle, "removeObjectByHandle")) { return nullptr; } int objectID = this->getObjectIDByHandle(objectHandle); if (objectID == ID_UNDEFINED) { return nullptr; } - return removeObjectInternal( - objectID, objectHandle, - "<" + this->objectType_ + ">::removeObjectByHandle"); + return removeObjectInternal(objectID, objectHandle, "removeObjectByHandle"); } /** @@ -461,6 +456,9 @@ class ManagedContainer : public ManagedContainerBase { */ template std::shared_ptr getObjectOrCopyByHandle(const std::string& objectHandle) { + static_assert(std::is_base_of::value, + "ManagedContainer :: Desired type must be derived from " + "Managed object type"); // call non-template version auto res = getObjectOrCopyByHandle(objectHandle); if (nullptr == res) { @@ -480,8 +478,7 @@ class ManagedContainer : public ManagedContainerBase { */ ManagedPtr getObjectCopyByID(int managedObjectID) { std::string objectHandle = getObjectHandleByID(managedObjectID); - if (!checkExistsWithMessage( - objectHandle, "<" + this->objectType_ + ">::getObjectCopyByID")) { + if (!checkExistsWithMessage(objectHandle, "getObjectCopyByID")) { return nullptr; } auto orig = getObjectInternal(objectHandle); @@ -496,8 +493,7 @@ class ManagedContainer : public ManagedContainerBase { * does not exist */ ManagedPtr getObjectCopyByHandle(const std::string& objectHandle) { - if (!checkExistsWithMessage(objectHandle, "<" + this->objectType_ + - ">::getObjectCopyByHandle")) { + if (!checkExistsWithMessage(objectHandle, "getObjectCopyByHandle")) { return nullptr; } auto orig = getObjectInternal(objectHandle); @@ -544,6 +540,9 @@ class ManagedContainer : public ManagedContainerBase { */ template std::shared_ptr getObjectCopyByID(int managedObjectID) { + static_assert(std::is_base_of::value, + "ManagedContainer :: Desired type must be derived from " + "Managed object type"); // call non-template version auto res = getObjectCopyByID(managedObjectID); if (nullptr == res) { @@ -563,6 +562,9 @@ class ManagedContainer : public ManagedContainerBase { */ template std::shared_ptr getObjectCopyByHandle(const std::string& objectHandle) { + static_assert(std::is_base_of::value, + "ManagedContainer :: Desired type must be derived from " + "Managed object type"); // call non-template version auto res = getObjectCopyByHandle(objectHandle); if (nullptr == res) { @@ -635,18 +637,22 @@ class ManagedContainer : public ManagedContainerBase { const std::string& src); /** - * @brief Build a shared pointer to a copy of a the passed managed object, - * of appropriate managed object type for passed object type. This is the - * function called by the copy constructor map. + * @brief This is the function called by the copy constructor map. Build a + * shared pointer to a copy of a the passed managed object, of appropriate + * managed object type for passed object type. + * * @tparam U Type of managed object being created - must be a derived class * of ManagedPtr * @param orig original object of type ManagedPtr being copied */ - template - ManagedPtr createObjectCopy(ManagedPtr& orig) { + template + ManagedPtr createObjCopyCtorMapEntry(ManagedPtr& orig) { + static_assert(std::is_base_of::value, + "ManagedContainer :: Desired type must be derived from " + "Managed object type"); // don't call init on copy - assume copy is already properly initialized. return U::create(*(static_cast(orig.get()))); - } // ManagedContainer:: + } // ManagedContainer::createObjCopyCtorMapEntry /** * @brief Build an @ref esp::core::managedContainers::AbstractManagedObject @@ -770,8 +776,7 @@ class ManagedContainer : public ManagedContainerBase { // original ManagedPtr managedObjectCopy = copyObject(object); // add to libraries - setObjectInternal(managedObjectCopy, objectHandle); - objectLibKeyByID_.emplace(objectID, objectHandle); + setObjectInternal(managedObjectCopy, objectID, objectHandle); return objectID; } // ManagedContainer::addObjectToLibrary @@ -817,8 +822,8 @@ auto ManagedContainer::removeObjectsBySubstring( getObjectHandlesBySubstring(subStr, contains); for (const std::string& objectHandle : handles) { int objID = this->getObjectIDByHandle(objectHandle); - ManagedPtr ptr = removeObjectInternal(objID, objectHandle, - "<" + this->objectType_ + ">"); + ManagedPtr ptr = + removeObjectInternal(objID, objectHandle, "removeObjectsBySubstring"); if (nullptr != ptr) { res.push_back(ptr); } @@ -832,19 +837,23 @@ auto ManagedContainer::removeObjectInternal( const std::string& objectHandle, const std::string& sourceStr) -> ManagedPtr { if (!checkExistsWithMessage(objectHandle, sourceStr)) { - ESP_DEBUG() << sourceStr << ": Unable to remove" << objectType_ - << "managed object" << objectHandle << ": Does not exist."; + ESP_DEBUG(Magnum::Debug::Flag::NoSpace) + << "<" + this->objectType_ + ">::" << sourceStr + << " : Unable to remove requested managed object `" << objectHandle + << "` : Does not exist."; return nullptr; } std::string msg; if (this->getIsUndeletable(objectHandle)) { msg = "Required Undeletable Managed Object"; } else if (this->getIsUserLocked(objectHandle)) { - msg = "User-locked Object. To delete managed object, unlock it"; + msg = "User-locked Object. To delete managed object, unlock it"; } if (msg.length() != 0) { - ESP_DEBUG() << sourceStr << ": Unable to remove" << objectType_ - << "managed object" << objectHandle << ":" << msg << "."; + ESP_DEBUG(Magnum::Debug::Flag::NoSpace) + << "<" + this->objectType_ + ">::" << sourceStr + << " : Unable to remove requested managed object `" << objectHandle + << "` : Object is a " << msg << "."; return nullptr; } ManagedPtr managedObject = getObjectInternal(objectHandle); diff --git a/src/esp/core/managedContainers/ManagedContainerBase.cpp b/src/esp/core/managedContainers/ManagedContainerBase.cpp index 099f2fc0ea..b7b4f25baf 100644 --- a/src/esp/core/managedContainers/ManagedContainerBase.cpp +++ b/src/esp/core/managedContainers/ManagedContainerBase.cpp @@ -15,8 +15,7 @@ namespace managedContainers { bool ManagedContainerBase::setLock(const std::string& objectHandle, bool lock) { // if managed object does not currently exist then do not attempt to modify // its lock state - if (!checkExistsWithMessage(objectHandle, - "<" + this->objectType_ + ">::setLock")) { + if (!checkExistsWithMessage(objectHandle, "setLock")) { return false; } // if setting lock else clearing lock diff --git a/src/esp/core/managedContainers/ManagedContainerBase.h b/src/esp/core/managedContainers/ManagedContainerBase.h index 6030f6f28a..aba0eb44be 100644 --- a/src/esp/core/managedContainers/ManagedContainerBase.h +++ b/src/esp/core/managedContainers/ManagedContainerBase.h @@ -92,7 +92,7 @@ class ManagedContainerBase { bool contains = true) { std::vector handles = getObjectHandlesBySubstring(subStr, contains); - return this->setLockByHandles(handles, lock); + return setLockByHandles(handles, lock); } // ManagedContainerBase::setLockBySubstring /** @@ -143,8 +143,8 @@ class ManagedContainerBase { * managed objects cannot be deleted, although they can be edited. */ std::vector getUndeletableObjectHandles() const { - std::vector res(this->undeletableObjectNames_.begin(), - this->undeletableObjectNames_.end()); + std::vector res(undeletableObjectNames_.begin(), + undeletableObjectNames_.end()); return res; } // ManagedContainerBase::getUndeletableObjectHandles @@ -154,7 +154,7 @@ class ManagedContainerBase { * @return True if handle exists and is undeletable. */ bool getIsUndeletable(const std::string& key) const { - return (this->undeletableObjectNames_.count(key) > 0); + return (undeletableObjectNames_.count(key) > 0); } /** @@ -164,8 +164,8 @@ class ManagedContainerBase { * locked. */ std::vector getUserLockedObjectHandles() const { - std::vector res(this->userLockedObjectNames_.begin(), - this->userLockedObjectNames_.end()); + std::vector res(userLockedObjectNames_.begin(), + userLockedObjectNames_.end()); return res; } // ManagedContainerBase::getUserLockedObjectHandles @@ -175,7 +175,7 @@ class ManagedContainerBase { * @return True if handle exists and is user-locked. */ bool getIsUserLocked(const std::string& key) const { - return (this->userLockedObjectNames_.count(key) > 0); + return (userLockedObjectNames_.count(key) > 0); } /** @@ -296,14 +296,16 @@ class ManagedContainerBase { } /** - * @brief Only used from class template AddObject method. put the passed + * @brief Only used from class template AddObject method. put the passed * smart poitner in the library. * @param ptr the smart pointer to the object being managed * @param handle the name (key) to use for the object in the library */ void setObjectInternal(const std::shared_ptr& ptr, + int objId, const std::string& handle) { objectLibrary_[handle] = ptr; + objectLibKeyByID_.emplace(objId, handle); } /** @@ -328,8 +330,9 @@ class ManagedContainerBase { const std::string& src) const { if (!getObjectLibHasHandle(objectHandle)) { ESP_ERROR(Magnum::Debug::Flag::NoSpace) - << src << ":" << objectType_ << " managed object handle `" - << objectHandle << "` not found in ManagedContainer, so aborting."; + << "<" + this->objectType_ + ">::" << src + << " : Managed object handle `" << objectHandle + << "` not found in ManagedContainer, so aborting."; return false; } return true; @@ -399,6 +402,26 @@ class ManagedContainerBase { bool contains, bool sorted) const; + /** + * @brief Get a list of all managed objects' handles of passed type whose + * origin handles contain substr, ignoring subStr's case. + * + * This version works on the internal objectLibKeyByID_ map + * @param subStr substring to search for within existing managed objects + * @param contains Whether to search for handles containing, or not + * containing, substr + * @param sorted whether the return vector values are sorted + * @return vector of 0 or more managed object handles containing/not + * containing the passed substring + */ + std::vector getAllObjectHandlesBySubStringPerType( + const std::string& subStr, + bool contains, + bool sorted) const { + return getObjectHandlesBySubStringPerType(objectLibKeyByID_, subStr, + contains, sorted); + } + /** * @brief Get a list of all managed objects' handles of passed type whose * origin handles contain substr, ignoring subStr's case. @@ -441,16 +464,40 @@ class ManagedContainerBase { virtual void resetFinalize() = 0; // ======== Instance Variables ======== - /** - * @brief Maps string keys to managed object managed objects - */ - std::unordered_map> objectLibrary_; /** @brief A descriptive name of the managed object being managed by this * manager. */ const std::string objectType_; + /** + * @brief Provide a const iterator over the @p objectLibrary_ + */ + std::pair< + std::unordered_map>::const_iterator, + std::unordered_map>::const_iterator> + getObjectLibIterator() const { + return std::make_pair(objectLibrary_.cbegin(), objectLibrary_.cend()); + } + + /** + * @brief Clear the mapping of undeletable object handles + */ + void clearUndeletableObjectNames() { undeletableObjectNames_.clear(); } + + /** + * @brief Add an undeleteable object's name to the mapping + */ + void addUndeletableObjectName(std::string objName) { + undeletableObjectNames_.insert(std::move(objName)); + } + + private: + /** + * @brief Maps string keys to managed object managed objects + */ + std::unordered_map> objectLibrary_; + /** * @brief Maps all object attribute IDs to the appropriate handles used * by lib diff --git a/src/esp/core/managedContainers/ManagedFileBasedContainer.h b/src/esp/core/managedContainers/ManagedFileBasedContainer.h index f7f0308766..d1bb7e701b 100644 --- a/src/esp/core/managedContainers/ManagedFileBasedContainer.h +++ b/src/esp/core/managedContainers/ManagedFileBasedContainer.h @@ -81,6 +81,9 @@ class ManagedFileBasedContainer : public ManagedContainer { const io::JsonGenericValue config = docConfig->GetObject(); ManagedFileIOPtr attr = this->buildManagedObjectFromDoc(filename, config); attr->setActualFilename(filename); + // Set attributes' status to saved (i.e. it matches the version on disk) + // since it was just loaded. + attr->setAttrIsSaved(); return this->postCreateRegister(std::move(attr), registerObject); } // ManagedFileBasedContainer::createObjectFromJSONFile @@ -110,6 +113,9 @@ class ManagedFileBasedContainer : public ManagedContainer { // convert doc to const value const io::JsonGenericValue config = docConfig->GetObject(); ManagedFileIOPtr attr = this->buildManagedObjectFromDoc(docName, config); + // Set attributes' status to saved (i.e. it matches the version on disk) + // since it was just built from an existing JSON string. + attr->setAttrIsSaved(); return this->postCreateRegister(std::move(attr), registerObject); } // ManagedFileBasedContainer::createObjectFromJSONString @@ -377,6 +383,8 @@ class ManagedFileBasedContainer : public ManagedContainer { // attributes. Note : this will not be "permanent" for the object unless // it is registered after this save. managedObject->setActualFilename(fullFilename); + // Set attributes' status to saved (i.e. it matches the version on disk) + managedObject->setAttrIsSaved(); } else { ESP_ERROR(Mn::Debug::Flag::NoSpace) << "<" << this->objectType_ << "> : Attempt to save to Filename `" diff --git a/src/esp/metadata/URDFParser.cpp b/src/esp/metadata/URDFParser.cpp index b7bc7f8091..46f17de59b 100644 --- a/src/esp/metadata/URDFParser.cpp +++ b/src/esp/metadata/URDFParser.cpp @@ -675,6 +675,16 @@ bool Parser::parseGeometry(Geometry& geom, const XMLElement* g) { return false; } else { parseVector3(geom.m_boxSize, shape->Attribute("size")); + if (geom.m_boxSize.min() == 0) { + ESP_ERROR() << "Collision box primitive with 0 scale detected " + << geom.m_boxSize + << ". Replacing zeros with 0.001 and continuing."; + for (int i = 0; i < 3; ++i) { + if (geom.m_boxSize[i] == 0) { + geom.m_boxSize[i] = 0.001; + } + } + } } } else if (type_name == "cylinder") { geom.m_type = GEOM_CYLINDER; diff --git a/src/esp/metadata/attributes/AbstractAttributes.cpp b/src/esp/metadata/attributes/AbstractAttributes.cpp index a1c3823101..6de0868cdc 100644 --- a/src/esp/metadata/attributes/AbstractAttributes.cpp +++ b/src/esp/metadata/attributes/AbstractAttributes.cpp @@ -22,6 +22,9 @@ AbstractAttributes::AbstractAttributes(const std::string& attributesClassKey, setHidden("__ID", 0); setHidden("__fileDirectory", ""); setHidden("__actualFilename", ""); + // Initialize attributes to be different than on version on disk, if one + // exists. This should be set to true on file load and on file save. + setHidden("__isAttrSaved", false); } } // namespace attributes diff --git a/src/esp/metadata/attributes/AbstractAttributes.h b/src/esp/metadata/attributes/AbstractAttributes.h index c51b28a555..ba414933d8 100644 --- a/src/esp/metadata/attributes/AbstractAttributes.h +++ b/src/esp/metadata/attributes/AbstractAttributes.h @@ -121,16 +121,36 @@ class AbstractAttributes return getSubconfigCopy("user_defined"); } + /** + * @brief Gets a const smart pointer reference to a view of the user-specified + * configuration data from config file. Habitat does not parse or process this + * data, but it will be available to the user via python bindings for each + * object. + */ + std::shared_ptr getUserConfigurationView() const { + return getSubconfigView("user_defined"); + } + /** * @brief Gets a smart pointer reference to the actual user-specified * configuration data from config file. Habitat does not parse or process this * data, but it will be available to the user via python bindings for each - * object. This method is for editing the configuration. + * object. This method is for editing the configuration. */ std::shared_ptr editUserConfiguration() { return editSubconfig("user_defined"); } + /** + * @brief Move an existing user_defined subconfiguration into this + * configuration, overwriting the existing copy if it exists. Habitat does not + * parse or process this data, but it will be available to the user via python + * bindings for each object. This method is for editing the configuration. + */ + void setUserConfiguration(std::shared_ptr& userAttr) { + setSubconfigPtr("user_defined", userAttr); + } + /** * @brief Returns the number of user-defined values (within the "user-defined" * sub-ConfigurationGroup) this attributes has. @@ -166,7 +186,42 @@ class AbstractAttributes getObjectInfoInternal()); } + /** + * @brief Check whether filepath-based fields have been set by user input + * but have not been verified to exist (such verification occurs when the + * attributes is registered.) + */ + bool getFilePathsAreDirty() const { return get("__fileNamesDirty"); } + + /** + * @brief Clear the flag that specifies that filepath-based fields have been + * set but not verfified to exist (such verification occurs when the + * attributes is registered.) + */ + void setFilePathsAreClean() { setHidden("__fileNamesDirty", false); } + + /** + * @brief Get whether this ManagedObject has been saved to disk in its current + * state. Only applicable to registered ManagedObjects + */ + bool isAttrSaved() const override { return get("__isAttrSaved"); } + protected: + /** + * @brief Set this ManagedObject's save status (i.e. whether it matches its + * version on disk or not) + */ + void setFileSaveStatus(bool _isSaved) override { + setHidden("__isAttrSaved", _isSaved); + } + + /** + * @brief Used internally only. Set the flag that specifies a filepath-based + * field has been set to some value but has not yet been verified to + * exist (such verification occurs when the attributes is registered.) + */ + void setFilePathsAreDirty() { setHidden("__fileNamesDirty", true); } + /** * @brief Changing access to setter so that Configuration bindings cannot be * used to set a reserved value to an incorrect type. The inheritors of this diff --git a/src/esp/metadata/attributes/AbstractObjectAttributes.cpp b/src/esp/metadata/attributes/AbstractObjectAttributes.cpp index 828ae95e3f..02debe8a6c 100644 --- a/src/esp/metadata/attributes/AbstractObjectAttributes.cpp +++ b/src/esp/metadata/attributes/AbstractObjectAttributes.cpp @@ -51,7 +51,7 @@ AbstractObjectAttributes::AbstractObjectAttributes( // This specifies that we want to investigate the state of the render and // collision handles before we allow this attributes to be registered. // Hidden field - setIsDirty(); + setFilePathsAreDirty(); // set up an existing subgroup for marker_sets attributes addOrEditSubgroup("marker_sets"); } // AbstractObjectAttributes ctor diff --git a/src/esp/metadata/attributes/AbstractObjectAttributes.h b/src/esp/metadata/attributes/AbstractObjectAttributes.h index f81b6351f5..be9258bb38 100644 --- a/src/esp/metadata/attributes/AbstractObjectAttributes.h +++ b/src/esp/metadata/attributes/AbstractObjectAttributes.h @@ -77,11 +77,18 @@ class AbstractObjectAttributes : public AbstractAttributes { double getUnitsToMeters() const { return get("units_to_meters"); } /** - * @brief If not visible can add dynamic non-rendered object into a scene. If - * is not visible then should not add object to drawables. + * @brief Set whether visible or not. If not visible can add dynamic + * non-rendered object into a scene. If is not visible then should not add + * object to drawables. */ void setIsVisible(bool isVisible) { set("is_visible", isVisible); } + /** + * @brief Get whether visible or not. If not visible can add dynamic + * non-rendered object into a scene. If is not visible then should not add + * object to drawables. + */ bool getIsVisible() const { return get("is_visible"); } + void setFrictionCoefficient(double frictionCoefficient) { set("friction_coefficient", frictionCoefficient); } @@ -114,7 +121,7 @@ class AbstractObjectAttributes : public AbstractAttributes { */ void setRenderAssetHandle(const std::string& renderAssetHandle) { set("render_asset", renderAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -133,7 +140,7 @@ class AbstractObjectAttributes : public AbstractAttributes { */ void setRenderAssetFullPath(const std::string& renderAssetHandle) { setHidden("__renderAssetFullPath", renderAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -272,7 +279,7 @@ class AbstractObjectAttributes : public AbstractAttributes { */ void setCollisionAssetHandle(const std::string& collisionAssetHandle) { set("collision_asset", collisionAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -291,7 +298,7 @@ class AbstractObjectAttributes : public AbstractAttributes { */ void setCollisionAssetFullPath(const std::string& collisionAssetHandle) { setHidden("__collisionAssetFullPath", collisionAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -501,9 +508,6 @@ class AbstractObjectAttributes : public AbstractAttributes { */ bool getForceFlatShading() const { return get("force_flat_shading"); } - bool getIsDirty() const { return get("__isDirty"); } - void setIsClean() { setHidden("__isDirty", false); } - /** * @brief Populate a json object with all the first-level values held in this * configuration. Default is overridden to handle special cases for @@ -587,7 +591,6 @@ class AbstractObjectAttributes : public AbstractAttributes { * @brief get AbstractObject specific info for csv string */ virtual std::string getAbstractObjectInfoInternal() const { return ""; }; - void setIsDirty() { setHidden("__isDirty", true); } public: ESP_SMART_POINTERS(AbstractObjectAttributes) diff --git a/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp b/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp index c54dd4832b..ba19c0b70c 100644 --- a/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp +++ b/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp @@ -16,6 +16,7 @@ ArticulatedObjectAttributes::ArticulatedObjectAttributes( init("render_asset", ""); init("semantic_id", 0); + init("is_visible", true); // Initialize the default base type to be free joint initTranslated("base_type", getAOBaseTypeName(ArticulatedObjectBaseType::Free)); @@ -41,7 +42,10 @@ ArticulatedObjectAttributes::ArticulatedObjectAttributes( // Initialize these so they exist in the configuration setHidden("__urdfFullPath", ""); setHidden("__renderAssetFullPath", ""); - + // This specifies that we want to investigate the state of the urdf and skin + // render asset handles before we allow this attributes to be registered. + // Hidden field + setFilePathsAreDirty(); // set up an existing subgroup for marker_sets attributes addOrEditSubgroup("marker_sets"); } // ArticulatedObjectAttributes ctor diff --git a/src/esp/metadata/attributes/ArticulatedObjectAttributes.h b/src/esp/metadata/attributes/ArticulatedObjectAttributes.h index 73da4fcbe3..87998b450d 100644 --- a/src/esp/metadata/attributes/ArticulatedObjectAttributes.h +++ b/src/esp/metadata/attributes/ArticulatedObjectAttributes.h @@ -53,6 +53,7 @@ class ArticulatedObjectAttributes : public AbstractAttributes { */ void setRenderAssetHandle(const std::string& renderAsset) { set("render_asset", renderAsset); + setFilePathsAreDirty(); } /** * @brief Gets the string name for the render asset relative path @@ -68,6 +69,7 @@ class ArticulatedObjectAttributes : public AbstractAttributes { */ void setRenderAssetFullPath(const std::string& renderAssetHandle) { setHidden("__renderAssetFullPath", renderAssetHandle); + setFilePathsAreDirty(); } /** @@ -99,6 +101,19 @@ class ArticulatedObjectAttributes : public AbstractAttributes { */ double getMassScale() const { return get("mass_scale"); } + /** + * @brief Set whether visible or not. If not visible can add dynamic + * non-rendered object into a scene. If is not visible then should not add + * object to drawables. + */ + void setIsVisible(bool isVisible) { set("is_visible", isVisible); } + /** + * @brief Get whether visible or not. If not visible can add dynamic + * non-rendered object into a scene. If is not visible then should not add + * object to drawables. + */ + bool getIsVisible() const { return get("is_visible"); } + /** * @brief Set the type of base/root joint to use to add this Articulated * Object to the world. Cannot be "UNSPECIFIED" diff --git a/src/esp/metadata/attributes/AttributesEnumMaps.cpp b/src/esp/metadata/attributes/AttributesEnumMaps.cpp index e585483104..1efdcbfe4d 100644 --- a/src/esp/metadata/attributes/AttributesEnumMaps.cpp +++ b/src/esp/metadata/attributes/AttributesEnumMaps.cpp @@ -206,6 +206,7 @@ std::string getShaderTypeName(ObjectInstanceShaderType shaderTypeVal) { const std::map InstanceTranslationOriginMap = { + {"default", SceneInstanceTranslationOrigin::Unknown}, {"asset_local", SceneInstanceTranslationOrigin::AssetLocal}, {"com", SceneInstanceTranslationOrigin::COM}, }; diff --git a/src/esp/metadata/attributes/PbrShaderAttributes.cpp b/src/esp/metadata/attributes/PbrShaderAttributes.cpp index cc2f1e4c8c..c063f75c58 100644 --- a/src/esp/metadata/attributes/PbrShaderAttributes.cpp +++ b/src/esp/metadata/attributes/PbrShaderAttributes.cpp @@ -28,16 +28,12 @@ PbrShaderAttributes::PbrShaderAttributes(const std::string& handle) // Default brdf lookup table is the brdflut from here: // https://github.com/SaschaWillems/Vulkan-glTF-PBR/blob/master/screenshots/tex_brdflut.png - // Setting the value directly so that it won't trigger the PbrIBLHelper handle - // creation. init("ibl_blut_filename", "brdflut_ldr_512x512.png"); - // Default equirectangular environment cube map - init("ibl_envmap_filename", "lythwood_room_1k.hdr"); - init("pbr_ibl_helper_key", - Cr::Utility::formatString("{}_{}", "brdflut_ldr_512x512", - "lythwood_room_1k.hdr")); + // Build the PbrIBLHelper key to check/retrive helpers in map in + // ResourceManager. + buildPbrShaderHelperKey("brdflut_ldr_512x512.png", "lythwood_room_1k.hdr"); init("tonemap_exposure", 4.5f); init("use_ibl_tonemap", true); diff --git a/src/esp/metadata/attributes/PbrShaderAttributes.h b/src/esp/metadata/attributes/PbrShaderAttributes.h index 2332c61925..252d852841 100644 --- a/src/esp/metadata/attributes/PbrShaderAttributes.h +++ b/src/esp/metadata/attributes/PbrShaderAttributes.h @@ -280,9 +280,8 @@ class PbrShaderAttributes : public AbstractAttributes { */ void setIBLBrdfLUTAssetHandle(const std::string& brdfLUTAsset) { set("ibl_blut_filename", brdfLUTAsset); - set("pbr_ibl_helper_key", - Cr::Utility::formatString("{}_{}", brdfLUTAsset, - get("ibl_envmap_filename"))); + buildPbrShaderHelperKey(brdfLUTAsset, + get("ibl_envmap_filename")); } /** * @brief Get the filename for the brdf lookup table used by the IBL @@ -299,9 +298,7 @@ class PbrShaderAttributes : public AbstractAttributes { */ void setIBLEnvMapAssetHandle(const std::string& envMapAsset) { set("ibl_envmap_filename", envMapAsset); - set("pbr_ibl_helper_key", - Cr::Utility::formatString( - "{}_{}", get("ibl_blut_filename"), envMapAsset)); + buildPbrShaderHelperKey(get("ibl_blut_filename"), envMapAsset); } /** @@ -319,7 +316,7 @@ class PbrShaderAttributes : public AbstractAttributes { * handle>'. */ std::string getPbrShaderHelperKey() const { - return get("pbr_ibl_helper_key"); + return get("__pbrIBLHelperKey"); } /** @@ -508,6 +505,17 @@ class PbrShaderAttributes : public AbstractAttributes { io::JsonAllocator& allocator) const override; protected: + /** + * @brief Used internally. Build the PbrShaderHelper Key from the ibl blut + * filename and the ibl envmap filename used to check/retrive helpers in map + * in ResourceManager. + */ + void buildPbrShaderHelperKey(const std::string& brdfLUTAsset, + const std::string& envMapAsset) { + setHidden("__pbrIBLHelperKey", + Cr::Utility::formatString("{}_{}", brdfLUTAsset, envMapAsset)); + } + /** * @brief Retrieve a comma-separated string holding the header values for the * info returned for this managed object, type-specific. diff --git a/src/esp/metadata/attributes/SceneInstanceAttributes.cpp b/src/esp/metadata/attributes/SceneInstanceAttributes.cpp index 48a1a97b07..254dded883 100644 --- a/src/esp/metadata/attributes/SceneInstanceAttributes.cpp +++ b/src/esp/metadata/attributes/SceneInstanceAttributes.cpp @@ -21,10 +21,12 @@ SceneObjectInstanceAttributes::SceneObjectInstanceAttributes( : AbstractAttributes(type, handle) { // default to unknown for object instances, to use attributes-specified // defaults - init("shader_type", getShaderTypeName(ObjectInstanceShaderType::Unspecified)); + initTranslated("shader_type", + getShaderTypeName(ObjectInstanceShaderType::Unspecified)); // defaults to unknown/undefined - init("motion_type", getMotionTypeName(esp::physics::MotionType::UNDEFINED)); + initTranslated("motion_type", + getMotionTypeName(esp::physics::MotionType::UNDEFINED)); // set to no rotation or translation init("rotation", Mn::Quaternion(Mn::Math::IdentityInit)); init("translation", Mn::Vector3()); @@ -32,8 +34,9 @@ SceneObjectInstanceAttributes::SceneObjectInstanceAttributes( // ID_UNDEFINED init("is_instance_visible", ID_UNDEFINED); // defaults to unknown so that obj instances use scene instance setting - init("translation_origin", - getTranslationOriginName(SceneInstanceTranslationOrigin::Unknown)); + initTranslated( + "translation_origin", + getTranslationOriginName(SceneInstanceTranslationOrigin::Unknown)); // set default multiplicative scaling values init("uniform_scale", 1.0); init("non_uniform_scale", Mn::Vector3{1.0, 1.0, 1.0}); @@ -50,18 +53,27 @@ SceneObjectInstanceAttributes::SceneObjectInstanceAttributes( // to a scene instance. // Handle is set via init in base class, which would not be written out to // file if we did not explicitly set it. + // NOTE : this will not call a virtual override + // (SceneAOInstanceAttributes::setHandle) of AbstractAttributes::setHandle due + // to virtual dispatch not being available in constructor setHandle(handle); // set appropriate fields from abstract object attributes // Not initialize, since these are not default values - set("shader_type", getShaderTypeName(baseObjAttribs->getShaderType())); - // set to match attributes setting - set("is_instance_visible", (baseObjAttribs->getIsVisible() ? 1 : 0)); + + // Need to verify that the baseObjAttribs values are not defaults before we + // set these values. + + if (!baseObjAttribs->isDefaultVal("shader_type")) { + setShaderType(getShaderTypeName(baseObjAttribs->getShaderType())); + } + if (!baseObjAttribs->isDefaultVal("is_visible")) { + setIsInstanceVisible(baseObjAttribs->getIsVisible()); + } // set nonuniform scale to match attributes scale - setNonUniformScale(baseObjAttribs->getScale()); - // Prepopulate user config to match baseObjAttribs' user config. - editUserConfiguration()->overwriteWithConfig( - baseObjAttribs->getUserConfiguration()); + if (!baseObjAttribs->isDefaultVal("scale")) { + setNonUniformScale(baseObjAttribs->getScale()); + } } std::string SceneObjectInstanceAttributes::getObjectInfoHeaderInternal() const { @@ -118,15 +130,10 @@ void SceneObjectInstanceAttributes::writeValuesToJson( io::JsonAllocator& allocator) const { // map "handle" to "template_name" key in json writeValueToJson("handle", "template_name", jsonObj, allocator); - if (getTranslation() != Mn::Vector3()) { - writeValueToJson("translation", jsonObj, allocator); - } - if (getTranslationOrigin() != SceneInstanceTranslationOrigin::Unknown) { - writeValueToJson("translation_origin", jsonObj, allocator); - } - if (getRotation() != Mn::Quaternion(Mn::Math::IdentityInit)) { - writeValueToJson("rotation", jsonObj, allocator); - } + writeValueToJson("translation", jsonObj, allocator); + writeValueToJson("translation_origin", jsonObj, allocator); + writeValueToJson("rotation", jsonObj, allocator); + // map "is_instance_visible" to boolean only if not -1, otherwise don't save int visSet = getIsInstanceVisible(); if (visSet != ID_UNDEFINED) { @@ -134,25 +141,12 @@ void SceneObjectInstanceAttributes::writeValuesToJson( auto jsonVal = io::toJsonValue(static_cast(visSet), allocator); jsonObj.AddMember("is_instance_visible", jsonVal, allocator); } - if (getMotionType() != esp::physics::MotionType::UNDEFINED) { - writeValueToJson("motion_type", jsonObj, allocator); - } - if (getShaderType() != ObjectInstanceShaderType::Unspecified) { - writeValueToJson("shader_type", jsonObj, allocator); - } - if (getUniformScale() != 1.0f) { - writeValueToJson("uniform_scale", jsonObj, allocator); - } - if (getNonUniformScale() != Mn::Vector3(1.0, 1.0, 1.0)) { - writeValueToJson("non_uniform_scale", jsonObj, allocator); - } - if (!getApplyScaleToMass()) { - writeValueToJson("apply_scale_to_mass", jsonObj, allocator); - } - if (getMassScale() != 1.0) { - writeValueToJson("mass_scale", jsonObj, allocator); - } - + writeValueToJson("motion_type", jsonObj, allocator); + writeValueToJson("shader_type", jsonObj, allocator); + writeValueToJson("uniform_scale", jsonObj, allocator); + writeValueToJson("non_uniform_scale", jsonObj, allocator); + writeValueToJson("apply_scale_to_mass", jsonObj, allocator); + writeValueToJson("mass_scale", jsonObj, allocator); // take care of child class values, if any exist writeValuesToJsonInternal(jsonObj, allocator); @@ -168,19 +162,21 @@ SceneAOInstanceAttributes::SceneAOInstanceAttributes(const std::string& handle) // Set the instance base type to be unspecified - if not set in instance json, // use ao_config value - init("base_type", getAOBaseTypeName(ArticulatedObjectBaseType::Unspecified)); + initTranslated("base_type", + getAOBaseTypeName(ArticulatedObjectBaseType::Unspecified)); // Set the instance source for the inertia calculation to be unspecified - if // not set in instance json, use ao_config value - init("inertia_source", - getAOInertiaSourceName(ArticulatedObjectInertiaSource::Unspecified)); + initTranslated( + "inertia_source", + getAOInertiaSourceName(ArticulatedObjectInertiaSource::Unspecified)); // Set the instance link order to use as unspecified - if not set in instance // json, use ao_config value - init("link_order", - getAOLinkOrderName(ArticulatedObjectLinkOrder::Unspecified)); + initTranslated("link_order", + getAOLinkOrderName(ArticulatedObjectLinkOrder::Unspecified)); // Set render mode to be unspecified - if not set in instance json, use // ao_config value - init("render_mode", - getAORenderModeName(ArticulatedObjectRenderMode::Unspecified)); + initTranslated("render_mode", + getAORenderModeName(ArticulatedObjectRenderMode::Unspecified)); editSubconfig("initial_joint_pose"); editSubconfig("initial_joint_velocities"); } @@ -194,27 +190,40 @@ SceneAOInstanceAttributes::SceneAOInstanceAttributes( // a scene instance. // Handle is set via init in base class, which would not be written out to // file if we did not explicitly set it. + // NOTE : this will not call a virtual override + // (SceneAOInstanceAttributes::setHandle) of AbstractAttributes::setHandle due + // to virtual dispatch not being available in constructor setHandle(handle); // Should not initialize these values but set them, since these are not // default values, but from an existing AO attributes. + + // Need to verify that the aObjAttribs values are not defaults before we + // set these values. // Set shader type to use aObjAttribs value - setShaderType(getShaderTypeName(aObjAttribs->getShaderType())); - // Set the instance base type to use aObjAttribs value - setBaseType(getAOBaseTypeName(aObjAttribs->getBaseType())); - // Set the instance source for the inertia calculation to use aObjAttribs - // value - setInertiaSource(getAOInertiaSourceName(aObjAttribs->getInertiaSource())); - // Set the instance link order to use aObjAttribs value - setLinkOrder(getAOLinkOrderName(aObjAttribs->getLinkOrder())); - // Set render mode to use aObjAttribs value - setRenderMode(getAORenderModeName(aObjAttribs->getRenderMode())); - - // Prepopulate user config to match attribs' user config. - editUserConfiguration()->overwriteWithConfig( - aObjAttribs->getUserConfiguration()); - editSubconfig("initial_joint_pose"); - editSubconfig("initial_joint_velocities"); + if (!aObjAttribs->isDefaultVal("shader_type")) { + setShaderType(getShaderTypeName(aObjAttribs->getShaderType())); + } + if (!aObjAttribs->isDefaultVal("is_visible")) { + setIsInstanceVisible(aObjAttribs->getIsVisible()); + } + if (!aObjAttribs->isDefaultVal("base_type")) { + // Set the instance base type to use aObjAttribs value + setBaseType(getAOBaseTypeName(aObjAttribs->getBaseType())); + } + if (!aObjAttribs->isDefaultVal("inertia_source")) { + // Set the instance source for the inertia calculation to use aObjAttribs + // value + setInertiaSource(getAOInertiaSourceName(aObjAttribs->getInertiaSource())); + } + if (!aObjAttribs->isDefaultVal("link_order")) { + // Set the instance link order to use aObjAttribs value + setLinkOrder(getAOLinkOrderName(aObjAttribs->getLinkOrder())); + } + if (!aObjAttribs->isDefaultVal("render_mode")) { + // Set render mode to use aObjAttribs value + setRenderMode(getAORenderModeName(aObjAttribs->getRenderMode())); + } } std::string SceneAOInstanceAttributes::getSceneObjInstanceInfoHeaderInternal() @@ -262,19 +271,10 @@ std::string SceneAOInstanceAttributes::getSceneObjInstanceInfoInternal() const { void SceneAOInstanceAttributes::writeValuesToJsonInternal( io::JsonGenericValue& jsonObj, io::JsonAllocator& allocator) const { - if (getBaseType() != ArticulatedObjectBaseType::Unspecified) { - writeValueToJson("base_type", jsonObj, allocator); - } - if (getInertiaSource() != ArticulatedObjectInertiaSource::Unspecified) { - writeValueToJson("inertia_source", jsonObj, allocator); - } - if (getLinkOrder() != ArticulatedObjectLinkOrder::Unspecified) { - writeValueToJson("link_order", jsonObj, allocator); - } - if (getRenderMode() != ArticulatedObjectRenderMode::Unspecified) { - writeValueToJson("render_mode", jsonObj, allocator); - } - + writeValueToJson("base_type", jsonObj, allocator); + writeValueToJson("inertia_source", jsonObj, allocator); + writeValueToJson("link_order", jsonObj, allocator); + writeValueToJson("render_mode", jsonObj, allocator); writeValueToJson("auto_clamp_joint_limits", jsonObj, allocator); } // SceneAOInstanceAttributes::writeValuesToJsonInternal diff --git a/src/esp/metadata/attributes/SceneInstanceAttributes.h b/src/esp/metadata/attributes/SceneInstanceAttributes.h index 9c6d95d02d..49807b762a 100644 --- a/src/esp/metadata/attributes/SceneInstanceAttributes.h +++ b/src/esp/metadata/attributes/SceneInstanceAttributes.h @@ -73,7 +73,7 @@ class SceneObjectInstanceAttributes : public AbstractAttributes { << translation_origin << "attempted to be set in SceneObjectInstanceAttributes :" << getHandle() << ". Aborting."); - set("translation_origin", translation_origin); + setTranslated("translation_origin", translation_origin); } /** @@ -93,6 +93,13 @@ class SceneObjectInstanceAttributes : public AbstractAttributes { return SceneInstanceTranslationOrigin::Unknown; } + /** + * @brief Get string representation of translation origin + */ + std::string getTranslationOriginStr() const { + return get("translation_origin"); + } + /** * @brief Set the rotation of the object */ @@ -145,7 +152,7 @@ class SceneObjectInstanceAttributes : public AbstractAttributes { << "attempted to be set in SceneObjectInstanceAttributes :" << getHandle() << ". Aborting."); - set("shader_type", shader_type); + setTranslated("shader_type", shader_type); } /** @@ -324,7 +331,7 @@ class SceneAOInstanceAttributes : public SceneObjectInstanceAttributes { << baseType << "attempted to be set in ArticulatedObjectAttributes:" << getHandle() << ". Aborting."); - set("base_type", baseType); + setTranslated("base_type", baseType); } /** @@ -356,7 +363,7 @@ class SceneAOInstanceAttributes : public SceneObjectInstanceAttributes { << inertiaSrc << "attempted to be set in ArticulatedObjectAttributes:" << getHandle() << ". Aborting."); - set("inertia_source", inertiaSrc); + setTranslated("inertia_source", inertiaSrc); } /** @@ -388,7 +395,7 @@ class SceneAOInstanceAttributes : public SceneObjectInstanceAttributes { << linkOrder << "attempted to be set in ArticulatedObjectAttributes:" << getHandle() << ". Aborting."); - set("link_order", linkOrder); + setTranslated("link_order", linkOrder); } /** @@ -419,7 +426,7 @@ class SceneAOInstanceAttributes : public SceneObjectInstanceAttributes { << renderMode << "attempted to be set in ArticulatedObjectAttributes:" << getHandle() << ". Aborting."); - set("render_mode", renderMode); + setTranslated("render_mode", renderMode); } /** diff --git a/src/esp/metadata/attributes/StageAttributes.h b/src/esp/metadata/attributes/StageAttributes.h index 7c7fbe9a24..e800fa28a4 100644 --- a/src/esp/metadata/attributes/StageAttributes.h +++ b/src/esp/metadata/attributes/StageAttributes.h @@ -82,7 +82,7 @@ class StageAttributes : public AbstractObjectAttributes { void setSemanticDescriptorFilename( const std::string& semantic_descriptor_filename) { set("semantic_descriptor_filename", semantic_descriptor_filename); - setIsDirty(); + setFilePathsAreDirty(); } /** * @brief Text file that describes the hierharchy of semantic information @@ -101,7 +101,7 @@ class StageAttributes : public AbstractObjectAttributes { void setSemanticDescriptorFullPath( const std::string& semanticDescriptorHandle) { setHidden("__semanticDescriptorFullPath", semanticDescriptorHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -121,7 +121,7 @@ class StageAttributes : public AbstractObjectAttributes { */ void setSemanticAssetHandle(const std::string& semanticAssetHandle) { set("semantic_asset", semanticAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -141,7 +141,7 @@ class StageAttributes : public AbstractObjectAttributes { */ void setSemanticAssetFullPath(const std::string& semanticAssetHandle) { setHidden("__semanticAssetFullPath", semanticAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** @@ -298,7 +298,7 @@ class StageAttributes : public AbstractObjectAttributes { void setNavmeshAssetHandle(const std::string& nav_asset) { set("nav_asset", nav_asset); - setIsDirty(); + setFilePathsAreDirty(); } std::string getNavmeshAssetHandle() const { return get("nav_asset"); @@ -311,7 +311,7 @@ class StageAttributes : public AbstractObjectAttributes { */ void setNavmeshAssetFullPath(const std::string& navmeshAssetHandle) { setHidden("__navmeshAssetFullPath", navmeshAssetHandle); - setIsDirty(); + setFilePathsAreDirty(); } /** diff --git a/src/esp/metadata/managers/AOAttributesManager.cpp b/src/esp/metadata/managers/AOAttributesManager.cpp index 1b26db54ca..5b047ef636 100644 --- a/src/esp/metadata/managers/AOAttributesManager.cpp +++ b/src/esp/metadata/managers/AOAttributesManager.cpp @@ -254,6 +254,8 @@ AOAttributesManager::preRegisterObjectFinalize( // filter all paths properly so that the handles don't have filepaths and the // accessors are hidden fields this->finalizeAttrPathsBeforeRegister(AOAttributesTemplate); + // Clear dirty flag from when asset handles are changed + AOAttributesTemplate->setFilePathsAreClean(); return core::managedContainers::ManagedObjectPreregistration::Success; } // AOAttributesManager::preRegisterObjectFinalize @@ -289,8 +291,11 @@ void AOAttributesManager::finalizeAttrPathsBeforeRegister( std::map AOAttributesManager::getArticulatedObjectModelFilenames() const { std::map articulatedObjPaths; - for (const auto& val : this->objectLibrary_) { - auto attr = this->getObjectByHandle(val.first); + + auto objIterPair = this->getObjectLibIterator(); + for (auto& objIter = objIterPair.first; objIter != objIterPair.second; + ++objIter) { + auto attr = this->getObjectByHandle(objIter->first); auto key = attr->getSimplifiedHandle(); auto urdf = attr->getURDFFullPath(); articulatedObjPaths[key] = urdf; diff --git a/src/esp/metadata/managers/AOAttributesManager.h b/src/esp/metadata/managers/AOAttributesManager.h index c415e133d2..b545718d75 100644 --- a/src/esp/metadata/managers/AOAttributesManager.h +++ b/src/esp/metadata/managers/AOAttributesManager.h @@ -28,7 +28,7 @@ class AOAttributesManager ManagedObjectAccess::Copy>:: AbstractAttributesManager("Articulated Object", "ao_config.json") { this->copyConstructorMap_["ArticulatedObjectAttributes"] = - &AOAttributesManager::createObjectCopy< + &AOAttributesManager::createObjCopyCtorMapEntry< attributes::ArticulatedObjectAttributes>; } // ctor @@ -43,7 +43,7 @@ class AOAttributesManager * overwritten with the newly created one if registerTemplate is true. * * @param aoConfigFilename The configuration file to parse. - * @param registerTemplate whether to add this template to the library. + * @param registerTemplate Whether to add this template to the library. * If the user is going to edit this template, this should be false - any * subsequent editing will require re-registration. Defaults to true. If * specified as true, then this function returns a copy of the registered diff --git a/src/esp/metadata/managers/AbstractAttributesManager.h b/src/esp/metadata/managers/AbstractAttributesManager.h index 5274f0c0ea..2ecd33b76f 100644 --- a/src/esp/metadata/managers/AbstractAttributesManager.h +++ b/src/esp/metadata/managers/AbstractAttributesManager.h @@ -425,7 +425,7 @@ AbstractAttributesManager::loadAllFileBasedTemplates( // save handles in list of defaults, so they are not removed, if desired. if (saveAsDefaults) { std::string tmpltHandle = tmplt->getHandle(); - this->undeletableObjectNames_.insert(std::move(tmpltHandle)); + this->addUndeletableObjectName(std::move(tmpltHandle)); } templateIndices[i] = tmplt->getID(); } diff --git a/src/esp/metadata/managers/AssetAttributesManager.cpp b/src/esp/metadata/managers/AssetAttributesManager.cpp index a5f08b0b67..0302915ef4 100644 --- a/src/esp/metadata/managers/AssetAttributesManager.cpp +++ b/src/esp/metadata/managers/AssetAttributesManager.cpp @@ -83,19 +83,25 @@ AssetAttributesManager::AssetAttributesManager() // function pointers to asset attributes copy constructors this->copyConstructorMap_["CapsulePrimitiveAttributes"] = - &AssetAttributesManager::createObjectCopy; + &AssetAttributesManager::createObjCopyCtorMapEntry< + CapsulePrimitiveAttributes>; this->copyConstructorMap_["ConePrimitiveAttributes"] = - &AssetAttributesManager::createObjectCopy; + &AssetAttributesManager::createObjCopyCtorMapEntry< + ConePrimitiveAttributes>; this->copyConstructorMap_["CubePrimitiveAttributes"] = - &AssetAttributesManager::createObjectCopy; + &AssetAttributesManager::createObjCopyCtorMapEntry< + CubePrimitiveAttributes>; this->copyConstructorMap_["CylinderPrimitiveAttributes"] = - &AssetAttributesManager::createObjectCopy; + &AssetAttributesManager::createObjCopyCtorMapEntry< + CylinderPrimitiveAttributes>; this->copyConstructorMap_["IcospherePrimitiveAttributes"] = - &AssetAttributesManager::createObjectCopy; + &AssetAttributesManager::createObjCopyCtorMapEntry< + IcospherePrimitiveAttributes>; this->copyConstructorMap_["UVSpherePrimitiveAttributes"] = - &AssetAttributesManager::createObjectCopy; + &AssetAttributesManager::createObjCopyCtorMapEntry< + UVSpherePrimitiveAttributes>; // no entry added for PrimObjTypes::END_PRIM_OBJ_TYPES - this->undeletableObjectNames_.clear(); + this->clearUndeletableObjectNames(); // build default AbstractPrimitiveAttributes objects for (const std::pair& elem : PrimitiveNames3DMap) { @@ -105,7 +111,7 @@ AssetAttributesManager::AssetAttributesManager() auto tmplt = AssetAttributesManager::createObject(elem.second, true); std::string tmpltHandle = tmplt->getHandle(); defaultPrimAttributeHandles_[elem.second] = tmpltHandle; - this->undeletableObjectNames_.insert(std::move(tmpltHandle)); + this->addUndeletableObjectName(std::move(tmpltHandle)); } ESP_DEBUG() << "Built default primitive asset templates :" diff --git a/src/esp/metadata/managers/AssetAttributesManager.h b/src/esp/metadata/managers/AssetAttributesManager.h index 3c084061e4..75bd106828 100644 --- a/src/esp/metadata/managers/AssetAttributesManager.h +++ b/src/esp/metadata/managers/AssetAttributesManager.h @@ -224,8 +224,7 @@ class AssetAttributesManager return {}; } std::string subStr = PrimitiveNames3DMap.at(primType); - return this->getObjectHandlesBySubStringPerType(this->objectLibKeyByID_, - subStr, contains, true); + return this->getAllObjectHandlesBySubStringPerType(subStr, contains, true); } // AssetAttributeManager::getTemplateHandlesByPrimType /** diff --git a/src/esp/metadata/managers/LightLayoutAttributesManager.h b/src/esp/metadata/managers/LightLayoutAttributesManager.h index 5a2fcc4b9b..ef3ca652ff 100644 --- a/src/esp/metadata/managers/LightLayoutAttributesManager.h +++ b/src/esp/metadata/managers/LightLayoutAttributesManager.h @@ -27,7 +27,7 @@ class LightLayoutAttributesManager "lighting_config.json") { // build this manager's copy constructor map this->copyConstructorMap_["LightLayoutAttributes"] = - &LightLayoutAttributesManager::createObjectCopy< + &LightLayoutAttributesManager::createObjCopyCtorMapEntry< attributes::LightLayoutAttributes>; } @@ -82,7 +82,9 @@ class LightLayoutAttributesManager const std::string& lightConfigName); /** - * @brief This function will be called to finalize attributes' paths before + * @brief Not required for this manager. + * + * This function will be called to finalize attributes' paths before * registration, moving fully qualified paths to the appropriate hidden * attribute fields. This can also be called without registration to make sure * the paths specified in an attributes are properly configured. diff --git a/src/esp/metadata/managers/ObjectAttributesManager.cpp b/src/esp/metadata/managers/ObjectAttributesManager.cpp index c193e64d65..fc374553bd 100644 --- a/src/esp/metadata/managers/ObjectAttributesManager.cpp +++ b/src/esp/metadata/managers/ObjectAttributesManager.cpp @@ -67,7 +67,7 @@ void ObjectAttributesManager::createDefaultPrimBasedAttributesTemplates() { auto tmplt = createPrimBasedAttributesTemplate(elem, true); // save handles in list of defaults, so they are not removed std::string tmpltHandle = tmplt->getHandle(); - this->undeletableObjectNames_.insert(std::move(tmpltHandle)); + this->addUndeletableObjectName(std::move(tmpltHandle)); } } // ObjectAttributesManager::createDefaultPrimBasedAttributesTemplates @@ -301,7 +301,7 @@ ObjectAttributesManager::preRegisterObjectFinalize( // accessors are hidden fields this->finalizeAttrPathsBeforeRegister(objectTemplate); // Clear dirty flag from when asset handles are changed - objectTemplate->setIsClean(); + objectTemplate->setFilePathsAreClean(); return core::managedContainers::ManagedObjectPreregistration::Success; } // ObjectAttributesManager::preRegisterObjectFinalize diff --git a/src/esp/metadata/managers/ObjectAttributesManager.h b/src/esp/metadata/managers/ObjectAttributesManager.h index d68d73ff98..de49f52ee7 100644 --- a/src/esp/metadata/managers/ObjectAttributesManager.h +++ b/src/esp/metadata/managers/ObjectAttributesManager.h @@ -29,7 +29,7 @@ class ObjectAttributesManager AbstractObjectAttributesManager("Object", "object_config.json") { // build this manager's copy constructor map this->copyConstructorMap_["ObjectAttributes"] = - &ObjectAttributesManager::createObjectCopy< + &ObjectAttributesManager::createObjCopyCtorMapEntry< attributes::ObjectAttributes>; } diff --git a/src/esp/metadata/managers/PbrShaderAttributesManager.cpp b/src/esp/metadata/managers/PbrShaderAttributesManager.cpp index 47e36f8edb..8bbcf939ec 100644 --- a/src/esp/metadata/managers/PbrShaderAttributesManager.cpp +++ b/src/esp/metadata/managers/PbrShaderAttributesManager.cpp @@ -23,7 +23,7 @@ PbrShaderAttributes::ptr PbrShaderAttributesManager::createObject( pbrConfigFilename, msg, registerTemplate); if (nullptr != attrs) { - ESP_DEBUG() << msg << "pbr shader configuration created" + ESP_DEBUG() << msg << "PBR Shader Attributes created" << (registerTemplate ? "and registered." : "."); } return attrs; @@ -218,7 +218,24 @@ void PbrShaderAttributesManager::setValsFromJSONDoc( // check for user defined attributes this->parseUserDefinedJsonVals(pbrShaderAttribs, jsonConfig); -} // PbrShaderAttributesManager::createFileBasedAttributesTemplate +} // PbrShaderAttributesManager::setValsFromJSONDoc + +core::managedContainers::ManagedObjectPreregistration +PbrShaderAttributesManager::preRegisterObjectFinalize( + attributes::PbrShaderAttributes::ptr pbrShaderAttribs, + const std::string& /*objectHandle*/, + bool /*forceRegistration*/) { + // TODO : Verify filenames exist as files or as resources + this->finalizeAttrPathsBeforeRegister(pbrShaderAttribs); + return core::managedContainers::ManagedObjectPreregistration::Success; +} // PbrShaderAttributesManager::preRegisterObjectFinalize + +void PbrShaderAttributesManager::finalizeAttrPathsBeforeRegister( + const attributes::PbrShaderAttributes::ptr& attributes) const { + // TODO Verify getIBLBrdfLUTAssetHandle and getIBLEnvMapAssetHandle exist as + // either file-based assets or resources and build paths to be relative if + // file-based +} // PbrShaderAttributesManager::finalizeAttrPathsBeforeRegister PbrShaderAttributes::ptr PbrShaderAttributesManager::initNewObjectInternal( const std::string& handleName, diff --git a/src/esp/metadata/managers/PbrShaderAttributesManager.h b/src/esp/metadata/managers/PbrShaderAttributesManager.h index ec075011dc..2512bc8e2b 100644 --- a/src/esp/metadata/managers/PbrShaderAttributesManager.h +++ b/src/esp/metadata/managers/PbrShaderAttributesManager.h @@ -27,7 +27,7 @@ class PbrShaderAttributesManager ManagedObjectAccess::Copy>:: AbstractAttributesManager("PBR Rendering", "pbr_config.json") { this->copyConstructorMap_["PbrShaderAttributes"] = - &PbrShaderAttributesManager::createObjectCopy< + &PbrShaderAttributesManager::createObjCopyCtorMapEntry< attributes::PbrShaderAttributes>; } // ctor @@ -70,11 +70,14 @@ class PbrShaderAttributesManager * to have IBL either on or off. */ void setAllIBLEnabled(bool isIblEnabled) { - for (const auto& val : this->objectLibrary_) { + auto objIterPair = this->getObjectLibIterator(); + for (auto& objIter = objIterPair.first; objIter != objIterPair.second; + ++objIter) { + const std::string objHandle = objIter->first; // Don't change system default - if (val.first.find(ESP_DEFAULT_PBRSHADER_CONFIG_REL_PATH) == + if (objHandle.find(ESP_DEFAULT_PBRSHADER_CONFIG_REL_PATH) == std::string::npos) { - this->getObjectByHandle(val.first)->setEnableIBL(isIblEnabled); + this->getObjectByHandle(objHandle)->setEnableIBL(isIblEnabled); } } } // PbrShaderAttributesManager::setAllIBLEnabled @@ -84,11 +87,14 @@ class PbrShaderAttributesManager * to have Direct Ligthing either on or off. */ void setAllDirectLightsEnabled(bool isDirLightEnabled) { - for (const auto& val : this->objectLibrary_) { + auto objIterPair = this->getObjectLibIterator(); + for (auto& objIter = objIterPair.first; objIter != objIterPair.second; + ++objIter) { + const std::string objHandle = objIter->first; // Don't change system default - if (val.first.find(ESP_DEFAULT_PBRSHADER_CONFIG_REL_PATH) == + if (objHandle.find(ESP_DEFAULT_PBRSHADER_CONFIG_REL_PATH) == std::string::npos) { - this->getObjectByHandle(val.first)->setEnableDirectLighting( + this->getObjectByHandle(objHandle)->setEnableDirectLighting( isDirLightEnabled); } } @@ -102,11 +108,11 @@ class PbrShaderAttributesManager * * TODO : If/When we begin treating IBL filepaths like we do other paths, this * will need to be implemented. - * @param attributes The attributes to be filtered. + * @param pbrShaderAttribs The attributes to be filtered. */ void finalizeAttrPathsBeforeRegister( - CORRADE_UNUSED const attributes::PbrShaderAttributes::ptr& attributes) - const override{}; + CORRADE_UNUSED const attributes::PbrShaderAttributes::ptr& + pbrShaderAttribs) const override; protected: /** @@ -139,12 +145,10 @@ class PbrShaderAttributesManager CORRADE_UNUSED const std::string& templateHandle) override {} /** - * @brief Not required for this manager. - * - * This method will perform any essential updating to the managed object - * before registration is performed. If this updating fails, registration will - * also fail. - * @param object the managed object to be registered + * @brief This method will perform any essential updating to the managed + * object before registration is performed. If this updating fails, + * registration will also fail. + * @param pbrShaderAttribs the managed object to be registered * @param objectHandle the name to register the managed object with. * Expected to be valid. * @param forceRegistration Should register object even if conditional @@ -154,12 +158,9 @@ class PbrShaderAttributesManager */ core::managedContainers::ManagedObjectPreregistration preRegisterObjectFinalize( - CORRADE_UNUSED attributes::PbrShaderAttributes::ptr object, + attributes::PbrShaderAttributes::ptr pbrShaderAttribs, CORRADE_UNUSED const std::string& objectHandle, - CORRADE_UNUSED bool forceRegistration) override { - // No pre-registration conditioning performed - return core::managedContainers::ManagedObjectPreregistration::Success; - } + CORRADE_UNUSED bool forceRegistration) override; /** * @brief Not required for this manager. diff --git a/src/esp/metadata/managers/PhysicsAttributesManager.h b/src/esp/metadata/managers/PhysicsAttributesManager.h index 524cc74049..e418fcee84 100644 --- a/src/esp/metadata/managers/PhysicsAttributesManager.h +++ b/src/esp/metadata/managers/PhysicsAttributesManager.h @@ -28,7 +28,7 @@ class PhysicsAttributesManager AbstractAttributesManager("Physics Manager", "physics_config.json") { this->copyConstructorMap_["PhysicsManagerAttributes"] = - &PhysicsAttributesManager::createObjectCopy< + &PhysicsAttributesManager::createObjCopyCtorMapEntry< attributes::PhysicsManagerAttributes>; } // ctor diff --git a/src/esp/metadata/managers/SceneDatasetAttributesManager.cpp b/src/esp/metadata/managers/SceneDatasetAttributesManager.cpp index ea800d7427..5d2932804c 100644 --- a/src/esp/metadata/managers/SceneDatasetAttributesManager.cpp +++ b/src/esp/metadata/managers/SceneDatasetAttributesManager.cpp @@ -25,7 +25,7 @@ SceneDatasetAttributesManager::SceneDatasetAttributesManager( pbrShaderAttributesManager_(std::move(pbrShaderAttributesMgr)) { // build this manager's copy ctor map this->copyConstructorMap_["SceneDatasetAttributes"] = - &SceneDatasetAttributesManager::createObjectCopy< + &SceneDatasetAttributesManager::createObjCopyCtorMapEntry< attributes::SceneDatasetAttributes>; } // SceneDatasetAttributesManager ctor diff --git a/src/esp/metadata/managers/SceneDatasetAttributesManager.h b/src/esp/metadata/managers/SceneDatasetAttributesManager.h index 59c1136b96..d95ca497de 100644 --- a/src/esp/metadata/managers/SceneDatasetAttributesManager.h +++ b/src/esp/metadata/managers/SceneDatasetAttributesManager.h @@ -67,8 +67,10 @@ class SceneDatasetAttributesManager */ void setCurrPhysicsManagerAttributesHandle(const std::string& handle) { physicsManagerAttributesHandle_ = handle; - for (const auto& val : this->objectLibrary_) { - this->getObjectByHandle(val.first)->setPhysicsManagerHandle(handle); + auto objIterPair = this->getObjectLibIterator(); + for (auto& objIter = objIterPair.first; objIter != objIterPair.second; + ++objIter) { + this->getObjectByHandle(objIter->first)->setPhysicsManagerHandle(handle); } } // SceneDatasetAttributesManager::setCurrPhysicsManagerAttributesHandle @@ -87,9 +89,11 @@ class SceneDatasetAttributesManager */ void setDefaultPbrShaderAttributesHandle(const std::string& pbrHandle) { defaultPbrShaderAttributesHandle_ = pbrHandle; - for (const auto& val : this->objectLibrary_) { - this->getObjectByHandle(val.first)->setDefaultPbrShaderAttrHandle( - pbrHandle); + auto objIterPair = this->getObjectLibIterator(); + for (auto& objIter = objIterPair.first; objIter != objIterPair.second; + ++objIter) { + this->getObjectByHandle(objIter->first) + ->setDefaultPbrShaderAttrHandle(pbrHandle); } } // SceneDatasetAttributesManager::setDefaultPbrShaderAttributesHandle diff --git a/src/esp/metadata/managers/SceneInstanceAttributesManager.cpp b/src/esp/metadata/managers/SceneInstanceAttributesManager.cpp index 5d8574dbf1..0494f951eb 100644 --- a/src/esp/metadata/managers/SceneInstanceAttributesManager.cpp +++ b/src/esp/metadata/managers/SceneInstanceAttributesManager.cpp @@ -375,9 +375,12 @@ void SceneInstanceAttributesManager::setAbstractObjectAttributesFromJson( instanceAttrs->setHandle(template_name); }); - // Check for translation origin override for a particular instance. Default + // Check for translation origin override for a particular instance. Default // to unknown, which will mean use scene instance-level default. - instanceAttrs->setTranslationOrigin(getTranslationOriginVal(jCell)); + const std::string transOriginStr = getTranslationOriginVal(jCell); + if (transOriginStr != instanceAttrs->getTranslationOriginStr()) { + instanceAttrs->setTranslationOrigin(getTranslationOriginVal(jCell)); + } // set specified shader type value. May be Unspecified, which means the // default value specified in the stage or object attributes will be used. diff --git a/src/esp/metadata/managers/SceneInstanceAttributesManager.h b/src/esp/metadata/managers/SceneInstanceAttributesManager.h index c7e4e2bc7a..1cf0776b1d 100644 --- a/src/esp/metadata/managers/SceneInstanceAttributesManager.h +++ b/src/esp/metadata/managers/SceneInstanceAttributesManager.h @@ -24,7 +24,7 @@ class SceneInstanceAttributesManager AbstractAttributesManager("Scene Instance", "scene_instance.json") { // build this manager's copy constructor map this->copyConstructorMap_["SceneInstanceAttributes"] = - &SceneInstanceAttributesManager::createObjectCopy< + &SceneInstanceAttributesManager::createObjCopyCtorMapEntry< attributes::SceneInstanceAttributes>; } diff --git a/src/esp/metadata/managers/SemanticAttributesManager.h b/src/esp/metadata/managers/SemanticAttributesManager.h index e6c10150fa..76d3e9adf1 100644 --- a/src/esp/metadata/managers/SemanticAttributesManager.h +++ b/src/esp/metadata/managers/SemanticAttributesManager.h @@ -27,7 +27,7 @@ class SemanticAttributesManager AbstractAttributesManager("Semantic Attributes", "semantic_config.json") { this->copyConstructorMap_["SemanticAttributes"] = - &SemanticAttributesManager::createObjectCopy< + &SemanticAttributesManager::createObjCopyCtorMapEntry< attributes::SemanticAttributes>; } // ctor diff --git a/src/esp/metadata/managers/StageAttributesManager.cpp b/src/esp/metadata/managers/StageAttributesManager.cpp index 9c786856a4..5b611ffa2a 100644 --- a/src/esp/metadata/managers/StageAttributesManager.cpp +++ b/src/esp/metadata/managers/StageAttributesManager.cpp @@ -32,7 +32,8 @@ StageAttributesManager::StageAttributesManager( cfgLightSetup_(NO_LIGHT_KEY) { // build this manager's copy constructor map this->copyConstructorMap_["StageAttributes"] = - &StageAttributesManager::createObjectCopy; + &StageAttributesManager::createObjCopyCtorMapEntry< + attributes::StageAttributes>; } // StageAttributesManager::ctor @@ -42,7 +43,7 @@ void StageAttributesManager::createDefaultPrimBasedAttributesTemplates() { auto tmplt = this->postCreateRegister( StageAttributesManager::initNewObjectInternal("NONE", false), true); std::string tmpltHandle = tmplt->getHandle(); - this->undeletableObjectNames_.insert(std::move(tmpltHandle)); + this->addUndeletableObjectName(std::move(tmpltHandle)); } // StageAttributesManager::createDefaultPrimBasedAttributesTemplates StageAttributes::ptr StageAttributesManager::createPrimBasedAttributesTemplate( @@ -460,8 +461,8 @@ StageAttributesManager::preRegisterObjectFinalize( // accessors are hidden fields this->finalizeAttrPathsBeforeRegister(stageAttributes); - - stageAttributes->setIsClean(); + // Clear dirty flag from when asset handles are changed + stageAttributes->setFilePathsAreClean(); return core::managedContainers::ManagedObjectPreregistration::Success; diff --git a/src/esp/physics/ArticulatedObject.h b/src/esp/physics/ArticulatedObject.h index 6ac578a1b0..54f73bc600 100644 --- a/src/esp/physics/ArticulatedObject.h +++ b/src/esp/physics/ArticulatedObject.h @@ -327,11 +327,11 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { /** * @brief Get a const reference to an ArticulatedLink SceneNode for * info query purposes. - * @param linkId The ArticulatedLink ID or -1 for the baseLink. + * @param linkId The ArticulatedLink ID or @ref BASELINK_ID for the @ref baseLink_. * @return Const reference to the SceneNode. */ - const scene::SceneNode& getLinkSceneNode(int linkId = -1) const { - if (linkId == ID_UNDEFINED) { + const scene::SceneNode& getLinkSceneNode(int linkId = BASELINK_ID) const { + if (linkId == BASELINK_ID) { // base link return baseLink_->node(); } @@ -345,12 +345,12 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { /** * @brief Get pointers to a link's visual SceneNodes. - * @param linkId The ArticulatedLink ID or -1 for the baseLink. + * @param linkId The ArticulatedLink ID or @ref BASELINK_ID for the @ref baseLink_. * @return vector of pointers to the link's visual scene nodes. */ std::vector getLinkVisualSceneNodes( - int linkId = -1) const { - if (linkId == ID_UNDEFINED) { + int linkId = BASELINK_ID) const { + if (linkId == BASELINK_ID) { // base link return baseLink_->visualNodes_; } @@ -404,12 +404,12 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { /** * @brief Get a link by index. * - * @param id The id of the desired link. -1 for base link. + * @param id The id of the desired link. @ref BASELINK_ID for the @ref baseLink_. * @return The desired link. */ ArticulatedLink& getLink(int id) { - // option to get the baseLink_ with id=-1 - if (id == -1) { + // option to get the baseLink_ with id=BASELINK_ID + if (id == BASELINK_ID) { return *baseLink_.get(); } @@ -420,14 +420,16 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { } /** - * @brief Get the number of links for this object (not including the base). + * @brief Get the number of links for this object (not including the @ref baseLink_ + * == @ref BASELINK_ID.). * * @return The number of non-base links. */ int getNumLinks() const { return links_.size(); } /** - * @brief Get a list of link ids, not including the base (-1). + * @brief Get a list of link ids, not including the @ref baseLink_ + * == @ref BASELINK_ID. * * @return A list of link ids for this object. */ @@ -441,14 +443,15 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { } /** - * @brief Get a list of link ids including the base (-1). + * @brief Get a list of link ids including the @ref baseLink_ + * == @ref BASELINK_ID. * * @return A list of link ids for this object. */ std::vector getLinkIdsWithBase() const { std::vector ids; ids.reserve(links_.size() + 1); - ids.push_back(-1); + ids.push_back(BASELINK_ID); for (auto it = links_.begin(); it != links_.end(); ++it) { ids.push_back(it->first); } @@ -488,14 +491,14 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { * @brief Given the list of passed points in this object's local space, return * those points transformed to world space. * @param points vector of points in object local space - * @param linkId Internal link index. + * @param linkId The ArticulatedLink ID or @ref BASELINK_ID for the @ref baseLink_. * @return vector of points transformed into world space */ std::vector transformLocalPointsToWorld( const std::vector& points, - int linkId = -1) const override { - if (linkId == -1) { - return this->baseLink_->transformLocalPointsToWorld(points, -1); + int linkId = BASELINK_ID) const override { + if (linkId == BASELINK_ID) { + return this->baseLink_->transformLocalPointsToWorld(points, BASELINK_ID); } auto linkIter = links_.find(linkId); ESP_CHECK(linkIter != links_.end(), @@ -509,14 +512,14 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { * @brief Given the list of passed points in world space, return * those points transformed to this object's local space. * @param points vector of points in world space - * @param linkId Internal link index. + * @param linkId The ArticulatedLink ID or @ref BASELINK_ID for the @ref baseLink_. * @return vector of points transformed to be in local space */ std::vector transformWorldPointsToLocal( const std::vector& points, - int linkId = -1) const override { - if (linkId == -1) { - return this->baseLink_->transformWorldPointsToLocal(points, -1); + int linkId = BASELINK_ID) const override { + if (linkId == BASELINK_ID) { + return this->baseLink_->transformWorldPointsToLocal(points, BASELINK_ID); } auto linkIter = links_.find(linkId); ESP_CHECK(linkIter != links_.end(), @@ -557,7 +560,7 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { int linkId = getLinkIdFromName(linkName); // locally access the unique pointer's payload const esp::physics::ArticulatedLink* aoLink = nullptr; - if (linkId == -1) { + if (linkId == BASELINK_ID) { aoLink = baseLink_.get(); } else { auto linkIter = links_.find(linkId); @@ -760,11 +763,11 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { /** * @brief Get the name of the link. * - * @param linkId The link's index. -1 for base link. + * @param linkId The link's index. @ref BASELINK_ID for the @ref baseLink_. * @return The link's name. */ virtual std::string getLinkName(int linkId) const { - if (linkId == -1) { + if (linkId == BASELINK_ID) { return baseLink_->linkName; } @@ -779,15 +782,17 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { * @brief Get the starting position for this link's parent joint in the global * DoFs array. * - * @param linkId The link's index. + * @param linkId The link's index. @ref BASELINK_ID for the @ref baseLink_. * @return The link's starting DoF index. */ - virtual int getLinkDoFOffset(CORRADE_UNUSED int linkId) const { return -1; } + virtual int getLinkDoFOffset(CORRADE_UNUSED int linkId) const { + return ID_UNDEFINED; + } /** * @brief Get the number of DoFs for this link's parent joint. * - * @param linkId The link's index. + * @param linkId The link's index. @ref BASELINK_ID for the @ref baseLink_. * @return The number of DoFs for this link's parent joint. */ virtual int getLinkNumDoFs(CORRADE_UNUSED int linkId) const { return 0; } @@ -796,17 +801,17 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { * @brief Get the starting position for this link's parent joint in the global * positions array. * - * @param linkId The link's index. + * @param linkId The link's index. @ref BASELINK_ID for the @ref baseLink_. * @return The link's starting position index. */ virtual int getLinkJointPosOffset(CORRADE_UNUSED int linkId) const { - return -1; + return ID_UNDEFINED; } /** * @brief Get the number of positions for this link's parent joint. * - * @param linkId The link's index. + * @param linkId The link's index. @ref BASELINK_ID for the @ref baseLink_. * @return The number of positions for this link's parent joint. */ virtual int getLinkNumJointPos(CORRADE_UNUSED int linkId) const { return 0; } @@ -975,7 +980,18 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase { return PhysicsObjectBase::getInitObjectInstanceAttrInternal< metadata::attributes::SceneAOInstanceAttributes>(); } - + /** + * @brief Returns a mutable copy of the @ref + * metadata::attributes::SceneAOInstanceAttributes used to place this + * Articulated Object initially in the scene. + * @return a read-only copy of the @ref metadata::attributes::SceneInstanceAttributes used to place + * this object in the scene. + */ + std::shared_ptr + getInitObjectInstanceAttrCopy() const { + return PhysicsObjectBase::getInitObjectInstanceAttrCopyInternal< + metadata::attributes::SceneAOInstanceAttributes>(); + } /** * @brief Return a @ref * metadata::attributes::SceneAOInstanceAttributes reflecting the current diff --git a/src/esp/physics/PhysicsManager.cpp b/src/esp/physics/PhysicsManager.cpp index 712b35041b..35875e2dd5 100644 --- a/src/esp/physics/PhysicsManager.cpp +++ b/src/esp/physics/PhysicsManager.cpp @@ -49,7 +49,6 @@ bool PhysicsManager::initPhysicsFinalize() { //! Create new scene node staticStageObject_ = physics::RigidStage::create(&physicsNode_->createChild(), resourceManager_); - return true; } @@ -57,6 +56,9 @@ PhysicsManager::~PhysicsManager() { ESP_DEBUG() << "Deconstructing PhysicsManager"; } +///////////////////////////////// +// Stage Creation + bool PhysicsManager::addStageInstance( const metadata::attributes::StageAttributes::ptr& initAttributes, const metadata::attributes::SceneObjectInstanceAttributes::cptr& @@ -123,7 +125,6 @@ int PhysicsManager::addObject(int attributesID, int PhysicsManager::addObjectInstance( const esp::metadata::attributes::SceneObjectInstanceAttributes::cptr& objInstAttributes, - bool defaultCOMCorrection, DrawableGroup* drawables, scene::SceneNode* attachmentNode, const std::string& lightSetup) { @@ -194,8 +195,7 @@ int PhysicsManager::addObjectInstance( objInstAttributes->getMassScale()); return addObjectAndSaveAttributes(objAttributes, drawables, attachmentNode, - lightSetup, defaultCOMCorrection, - objInstAttributes); + lightSetup, objInstAttributes); } // PhysicsManager::addObjectInstance @@ -210,16 +210,14 @@ int PhysicsManager::cloneExistingObject(int objectID) { return ID_UNDEFINED; } auto objPtr = existingObjIter->second; - // Get object instance attributes copy - esp::metadata::attributes::SceneObjectInstanceAttributes::cptr objInstAttrs = - objPtr->getInitObjectInstanceAttr(); - // Create object instance - int newObjID = addObjectInstance(objInstAttrs, objPtr->isCOMCorrected(), - &simulator_->getDrawableGroup(), nullptr, - simulator_->getCurrentLightSetupKey()); + // Get object instance attributes copy with current state of object instance + esp::metadata::attributes::SceneObjectInstanceAttributes::ptr + newObjInstAttrs = objPtr->getCurrentStateInstanceAttr(); - // Update new object's values if necessary - // auto newObject = existingObjects_.find(newObjID); + // Create object instance + int newObjID = + addObjectInstance(newObjInstAttrs, &simulator_->getDrawableGroup(), + nullptr, simulator_->getCurrentLightSetupKey()); return newObjID; @@ -230,16 +228,20 @@ int PhysicsManager::addObjectAndSaveAttributes( DrawableGroup* drawables, scene::SceneNode* attachmentNode, const std::string& lightSetup, - bool defaultCOMCorrection, esp::metadata::attributes::SceneObjectInstanceAttributes::cptr objInstAttributes) { - // If no drawables were passed, and a simulator exists - // retrieve a drawable group to use - if ((drawables == nullptr) && (simulator_ != nullptr)) { - // acquire context if available - simulator_->getRenderGLContext(); - // acquire an appropriate drawable group - drawables = &simulator_->getDrawableGroup(); + bool defaultCOMCorrection = false; + if (simulator_ != nullptr) { + // get defaultCOMCorrection from simulator + defaultCOMCorrection = simulator_->getCurSceneDefaultCOMHandling(); + // If no drawables were passed, and a simulator exists + // retrieve a drawable group to use + if (drawables == nullptr) { + // acquire context if available + simulator_->getRenderGLContext(); + // acquire an appropriate drawable group + drawables = &simulator_->getDrawableGroup(); + } } if (objInstAttributes == nullptr) { @@ -387,6 +389,7 @@ int PhysicsManager::addObjectInternal( ///////////////////////////////// // Articulated Object Creation + int PhysicsManager::addArticulatedObject(const std::string& attributesHandle, DrawableGroup* drawables, bool forceReload, @@ -580,17 +583,15 @@ int PhysicsManager::cloneExistingArticulatedObject(int aObjectID) { return ID_UNDEFINED; } auto aObjPtr = existingAOIter->second; - // Get object instance attributes copy - esp::metadata::attributes::SceneAOInstanceAttributes::cptr artObjInstAttrs = - aObjPtr->getInitObjectInstanceAttr(); + // Get articulated object instance attributes copy with current state of AO + esp::metadata::attributes::SceneAOInstanceAttributes::ptr artObjInstAttrs = + aObjPtr->getCurrentStateInstanceAttr(); + // Create object instance int newArtObjID = addArticulatedObjectInstance( artObjInstAttrs, &simulator_->getDrawableGroup(), simulator_->getCurrentLightSetupKey()); - // Update new object's values if necessary - // auto newArtObj = existingArticulatedObjects_.find(newArtObjID); - return newArtObjID; } // PhysicsManager::cloneExistingArticulatedObject @@ -804,7 +805,7 @@ void PhysicsManager::removeObject(const int objectId, trajVisIDByName.erase(trajVisAssetName); // TODO : if object is trajectory visualization, remove its assets as // well once this is supported. - // resourceManager_->removeResourceByName(trajVisAssetName); + // resourceManager_.removeResourceByName(trajVisAssetName); } } // PhysicsManager::removeObject diff --git a/src/esp/physics/PhysicsManager.h b/src/esp/physics/PhysicsManager.h index 29296c449d..65ffbb62d2 100644 --- a/src/esp/physics/PhysicsManager.h +++ b/src/esp/physics/PhysicsManager.h @@ -92,10 +92,13 @@ struct RaycastResults { * @brief based on Bullet b3ContactPointData */ struct ContactPointData { - int objectIdA = -2; // stage is -1 - int objectIdB = -2; - int linkIndexA = -1; // -1 if not a multibody - int linkIndexB = -1; + // Initialize to safe, appropriate values + // stage will be lowest object ID in system + int objectIdA = RIGID_STAGE_ID - 1; + int objectIdB = RIGID_STAGE_ID - 1; + // assume not a multibody + int linkIndexA = ID_UNDEFINED; + int linkIndexB = ID_UNDEFINED; Magnum::Vector3 positionOnAInWS; // contact point location on object A, in // world space coordinates @@ -160,12 +163,11 @@ struct RigidConstraintSettings { /** @brief objectIdB == ID_UNDEFINED indicates "world". */ int objectIdB = ID_UNDEFINED; - /** @brief link of objectA if articulated. ID_UNDEFINED(-1) refers to base. - */ - int linkIdA = ID_UNDEFINED; + /** @brief link of objectA if articulated. @ref BASELINK_ID refers to base.*/ + int linkIdA = BASELINK_ID; - /** @brief link of objectB if articulated. ID_UNDEFINED(-1) refers to base.*/ - int linkIdB = ID_UNDEFINED; + /** @brief link of objectB if articulated. @ref BASELINK_ID refers to base.*/ + int linkIdB = BASELINK_ID; /** @brief constraint point in local space of respective objects*/ Mn::Vector3 pivotA{}, pivotB{}; @@ -264,16 +266,24 @@ class PhysicsManager : public std::enable_shared_from_this { /** * @brief Reset the simulation and physical world. - * Sets the @ref worldTime_ to 0.0, changes the physical state of all objects back to their initial states. Only changes motion_type when scene_instance specified a motion type. - */ - virtual void reset() { + * Sets the @ref worldTime_ to 0.0, changes the physical + * state of all objects back to their initial states. + * Only changes motion_type when scene_instance specified a motion type. + * @param calledAfterSceneCreate If this is true, this is being called + * directly after a new scene was created and all the objects were placed + * appropriately, so bypass object placement reset code. + */ + virtual void reset(bool calledAfterSceneCreate) { // reset object states from initial values (e.g. from scene instance) worldTime_ = 0.0; - for (const auto& bro : existingObjects_) { - bro.second->resetStateFromSceneInstanceAttr(); - } - for (const auto& bao : existingArticulatedObjects_) { - bao.second->resetStateFromSceneInstanceAttr(); + if (!calledAfterSceneCreate) { + // No need to re-place objects after scene creation + for (const auto& bro : existingObjects_) { + bro.second->resetStateFromSceneInstanceAttr(); + } + for (const auto& bao : existingArticulatedObjects_) { + bao.second->resetStateFromSceneInstanceAttr(); + } } } @@ -317,7 +327,6 @@ class PhysicsManager : public std::enable_shared_from_this { int addObjectInstance( const esp::metadata::attributes::SceneObjectInstanceAttributes::cptr& objInstAttributes, - bool defaultCOMCorrection = false, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY); @@ -983,9 +992,6 @@ class PhysicsManager : public std::enable_shared_from_this { * @param attachmentNode If supplied, attach the new physical object to an * existing SceneNode. * @param lightSetup The string name of the desired lighting setup to use. - * @param defaultCOMCorrection The default value of whether COM-based - * translation correction needs to occur. Only non-default from - * addObjectInstance method. * @param objInstAttributes The attributes that describe the desired state to * set this object on creation. If nullptr, create an empty default instance * and populate it properly based on the object config. @@ -997,7 +1003,6 @@ class PhysicsManager : public std::enable_shared_from_this { DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY, - bool defaultCOMCorrection = false, esp::metadata::attributes::SceneObjectInstanceAttributes::cptr objInstAttributes = nullptr); diff --git a/src/esp/physics/PhysicsObjectBase.h b/src/esp/physics/PhysicsObjectBase.h index ade6e34b3c..b9f70b511c 100644 --- a/src/esp/physics/PhysicsObjectBase.h +++ b/src/esp/physics/PhysicsObjectBase.h @@ -97,10 +97,10 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { */ template std::shared_ptr getInitializationAttributes() const { - if (!initializationAttributes_) { + if (!objInitAttributes_) { return nullptr; } - return T::create(*(static_cast(initializationAttributes_.get()))); + return T::create(*(static_cast(objInitAttributes_.get()))); } /** @@ -229,7 +229,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { */ virtual std::vector transformLocalPointsToWorld( const std::vector& points, - CORRADE_UNUSED int linkID = -1) const { + CORRADE_UNUSED int linkID = ID_UNDEFINED) const { std::vector wsPoints; wsPoints.reserve(points.size()); Mn::Vector3 objScale = getScale(); @@ -249,7 +249,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { */ virtual std::vector transformWorldPointsToLocal( const std::vector& points, - CORRADE_UNUSED int linkID = -1) const { + CORRADE_UNUSED int linkID = ID_UNDEFINED) const { std::vector lsPoints; lsPoints.reserve(points.size()); Mn::Vector3 objScale = getScale(); @@ -479,7 +479,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { template void setSceneInstanceAttr(std::shared_ptr instanceAttr) { - _initObjInstanceAttrs = std::move(instanceAttr); + _objInstanceInitAttributes = std::move(instanceAttr); } // setSceneInstanceAttr /** @@ -584,7 +584,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { for (const auto& markersEntry : linkEntry.second) { const std::string markersName = markersEntry.first; perLinkMap[markersName] = - transformLocalPointsToWorld(markersEntry.second, -1); + transformLocalPointsToWorld(markersEntry.second, ID_UNDEFINED); } perTaskMap[linkName] = perLinkMap; } @@ -593,33 +593,68 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { return res; } // getMarkerPointsGlobal - /** @brief Get the scale of the object set during initialization. + /** + * @brief Get the scale of the object set during initialization. * @return The scaling for the object relative to its initially loaded meshes. */ virtual Magnum::Vector3 getScale() const { return _creationScale; } - /** @brief Return whether or not this object is articulated. Override in - * ArticulatedObject */ + /** + * @brief Return whether or not this object is articulated. Override in + * ArticulatedObject + */ bool isArticulated() const { return _isArticulated; } /** @brief Return the local axis-aligned bounding box of the this object.*/ virtual const Mn::Range3D& getAabb() { return node().getCumulativeBB(); } protected: + /** + * @brief Used Internally on object creation. Set whether or not this object + * is articulated. + */ void setIsArticulated(bool isArticulated) { _isArticulated = isArticulated; } - /** @brief Accessed internally. Get an appropriately cast copy of the @ref + /** + * @brief Accessed internally. Get an appropriately cast copy of the @ref * metadata::attributes::SceneObjectInstanceAttributes used to place the * object within the scene. * @return A copy of the initialization template used to create this object * instance or nullptr if no template exists. */ template - std::shared_ptr getInitObjectInstanceAttrInternal() const { - if (!_initObjInstanceAttrs) { + std::shared_ptr getInitObjectInstanceAttrCopyInternal() const { + if (!_objInstanceInitAttributes) { + return nullptr; + } + static_assert( + std::is_base_of::value, + "SceneObjectInstanceAttributes must be base class of desired instance " + "attributes class."); + return T::create( + *(static_cast(_objInstanceInitAttributes.get()))); + } + + /** + * @brief Accessed internally. Get the + * @ref metadata::attributes::SceneObjectInstanceAttributes used to + * create and place the object within the scene, appropriately cast for + * object type. + * @return A copy of the initialization template used to create this object + * instance or nullptr if no template exists. + */ + template + std::shared_ptr getInitObjectInstanceAttrInternal() const { + if (!_objInstanceInitAttributes) { return nullptr; } - return T::create(*(static_cast(_initObjInstanceAttrs.get()))); + static_assert( + std::is_base_of::value, + "SceneObjectInstanceAttributes must be base class of desired instance " + "attributes class."); + return std::static_pointer_cast(_objInstanceInitAttributes); } /** @@ -639,7 +674,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { */ template std::shared_ptr getCurrentObjectInstanceAttrInternal() { - if (!_initObjInstanceAttrs) { + if (!_objInstanceInitAttributes) { return nullptr; } static_assert( @@ -648,15 +683,37 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { "PhysicsObjectBase : Cast of SceneObjectInstanceAttributes must be to " "class that inherits from SceneObjectInstanceAttributes"); - std::shared_ptr initAttrs = std::const_pointer_cast( - T::create(*(static_cast(_initObjInstanceAttrs.get())))); + std::shared_ptr initObjInstAttrsCopy = std::const_pointer_cast( + T::create(*(static_cast(_objInstanceInitAttributes.get())))); // set values - initAttrs->setTranslation(getUncorrectedTranslation()); - initAttrs->setRotation(getRotation()); - initAttrs->setMotionType( - metadata::attributes::getMotionTypeName(objectMotionType_)); + const auto translation = getUncorrectedTranslation(); + if (initObjInstAttrsCopy->getTranslation() != translation) { + initObjInstAttrsCopy->setTranslation(translation); + } + const auto rotation = getRotation(); + if (initObjInstAttrsCopy->getRotation() != rotation) { + initObjInstAttrsCopy->setRotation(rotation); + } + // only change if different + if (initObjInstAttrsCopy->getMotionType() != objectMotionType_) { + initObjInstAttrsCopy->setMotionType( + metadata::attributes::getMotionTypeName(objectMotionType_)); + } + + // temp copy of object's user attributes. Treated as ground truth for user + // attributes. + core::config::Configuration::ptr tmpUserAttrs = + core::config::Configuration::create(*userAttributes_); - return initAttrs; + // now filter this by the creation attributes' copy. NOTE if the creation + // attributes themselves are different than the same-named versions on disk, + // these values may be out of sync. + tmpUserAttrs->filterFromConfig( + objInitAttributes_->getUserConfigurationView()); + // copy these over the existing user defined fields + // in the instance + initObjInstAttrsCopy->setUserConfiguration(tmpUserAttrs); + return initObjInstAttrsCopy; } /** @@ -711,8 +768,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { /** * @brief Saved template attributes when the object was initialized. */ - metadata::attributes::AbstractAttributes::cptr initializationAttributes_ = - nullptr; + metadata::attributes::AbstractAttributes::cptr objInitAttributes_ = nullptr; /** * @brief Set the object's creation scale @@ -727,7 +783,7 @@ class PhysicsObjectBase : public Magnum::SceneGraph::AbstractFeature3D { * creation. */ std::shared_ptr - _initObjInstanceAttrs = nullptr; + _objInstanceInitAttributes = nullptr; /** * @brief The scale applied to this object on creation diff --git a/src/esp/physics/RigidBase.h b/src/esp/physics/RigidBase.h index c7d172d7da..a8e0a34e10 100644 --- a/src/esp/physics/RigidBase.h +++ b/src/esp/physics/RigidBase.h @@ -287,6 +287,18 @@ class RigidBase : public esp::physics::PhysicsObjectBase { metadata::attributes::SceneObjectInstanceAttributes>(); } + /** + * @brief Returns a mutable copy of the @ref metadata::attributes::SceneObjectInstanceAttributes + * used to place this rigid object in the scene. + * @return a read-only copy of the @ref metadata::attributes::SceneInstanceAttributes used to place + * this object in the scene. + */ + std::shared_ptr + getInitObjectInstanceAttrCopy() const { + return PhysicsObjectBase::getInitObjectInstanceAttrCopyInternal< + metadata::attributes::SceneObjectInstanceAttributes>(); + } + /** * @brief Return a @ref * metadata::attributes::SceneObjectInstanceAttributes reflecting the current diff --git a/src/esp/physics/RigidObject.cpp b/src/esp/physics/RigidObject.cpp index 245e168df6..d0621ed07c 100644 --- a/src/esp/physics/RigidObject.cpp +++ b/src/esp/physics/RigidObject.cpp @@ -15,7 +15,7 @@ RigidObject::RigidObject(scene::SceneNode* rigidBodyNode, bool RigidObject::initialize( metadata::attributes::AbstractObjectAttributes::ptr initAttributes) { - if (initializationAttributes_ != nullptr) { + if (objInitAttributes_ != nullptr) { ESP_ERROR() << "Cannot initialize a RigidObject more than once"; return false; } @@ -26,7 +26,7 @@ bool RigidObject::initialize( // time setUserAttributes(initAttributes->getUserConfiguration()); setMarkerSets(initAttributes->getMarkerSetsConfiguration()); - initializationAttributes_ = std::move(initAttributes); + objInitAttributes_ = std::move(initAttributes); return initialization_LibSpecific(); } // RigidObject::initialize @@ -37,7 +37,7 @@ bool RigidObject::finalizeObject() { // cast initialization attributes metadata::attributes::ObjectAttributes::cptr ObjectAttributes = std::dynamic_pointer_cast( - initializationAttributes_); + objInitAttributes_); if (!ObjectAttributes->getComputeCOMFromShape()) { // will be false if the COM is provided; shift by that COM @@ -91,7 +91,7 @@ void RigidObject::resetStateFromSceneInstanceAttr() { // set object's motion type if different than set value const physics::MotionType attrObjMotionType = - static_cast(sceneInstanceAttr->getMotionType()); + sceneInstanceAttr->getMotionType(); if (attrObjMotionType != physics::MotionType::UNDEFINED) { this->setMotionType(attrObjMotionType); } diff --git a/src/esp/physics/RigidStage.cpp b/src/esp/physics/RigidStage.cpp index 2d11f37a25..1186658dca 100644 --- a/src/esp/physics/RigidStage.cpp +++ b/src/esp/physics/RigidStage.cpp @@ -13,7 +13,7 @@ RigidStage::RigidStage(scene::SceneNode* rigidBodyNode, bool RigidStage::initialize( metadata::attributes::AbstractObjectAttributes::ptr initAttributes) { - if (initializationAttributes_ != nullptr) { + if (objInitAttributes_ != nullptr) { ESP_ERROR() << "Cannot initialize a RigidStage more than once"; return false; } @@ -26,7 +26,7 @@ bool RigidStage::initialize( // time setUserAttributes(initAttributes->getUserConfiguration()); setMarkerSets(initAttributes->getMarkerSetsConfiguration()); - initializationAttributes_ = std::move(initAttributes); + objInitAttributes_ = std::move(initAttributes); return initialization_LibSpecific(); } diff --git a/src/esp/physics/bullet/BulletArticulatedObject.cpp b/src/esp/physics/bullet/BulletArticulatedObject.cpp index 9a6e15d0b2..eef0c6e965 100644 --- a/src/esp/physics/bullet/BulletArticulatedObject.cpp +++ b/src/esp/physics/bullet/BulletArticulatedObject.cpp @@ -172,7 +172,7 @@ void BulletArticulatedObject::initializeFromURDF( // set user config and initialization attributes setUserAttributes(initAttributes->getUserConfiguration()); setMarkerSets(initAttributes->getMarkerSetsConfiguration()); - initializationAttributes_ = initAttributes; + objInitAttributes_ = initAttributes; } void BulletArticulatedObject::constructStaticRigidBaseObject() { diff --git a/src/esp/physics/bullet/BulletPhysicsManager.cpp b/src/esp/physics/bullet/BulletPhysicsManager.cpp index e31f7867d8..ce09ed0b3d 100644 --- a/src/esp/physics/bullet/BulletPhysicsManager.cpp +++ b/src/esp/physics/bullet/BulletPhysicsManager.cpp @@ -162,7 +162,7 @@ int BulletPhysicsManager::addArticulatedObjectInternal( } // allocate ids for links - ArticulatedLink& rootObject = articulatedObject->getLink(-1); + ArticulatedLink& rootObject = articulatedObject->getLink(BASELINK_ID); rootObject.node().setBaseObjectId(articulatedObject->getObjectID()); for (int linkIx = 0; linkIx < articulatedObject->btMultiBody_->getNumLinks(); ++linkIx) { @@ -536,7 +536,7 @@ void BulletPhysicsManager::lookUpObjectIdAndLinkId( CORRADE_INTERNAL_ASSERT(objectId); CORRADE_INTERNAL_ASSERT(linkId); - *linkId = -1; + *linkId = ID_UNDEFINED; // If the lookup fails, default to the stage. TODO: better error-handling. *objectId = RIGID_STAGE_ID; auto rawColObjIdIter = collisionObjToObjIds_->find(colObj); @@ -572,10 +572,10 @@ std::vector BulletPhysicsManager::getContactPoints() const { const btPersistentManifold* manifold = dispatcher->getInternalManifoldPointer()[i]; - int objectIdA = ID_UNDEFINED; - int objectIdB = ID_UNDEFINED; - int linkIndexA = -1; // -1 if not a multibody - int linkIndexB = -1; + int objectIdA = RIGID_STAGE_ID - 1; + int objectIdB = RIGID_STAGE_ID - 1; + int linkIndexA = ID_UNDEFINED; // -1 if not a multibody + int linkIndexB = ID_UNDEFINED; const btCollisionObject* colObj0 = manifold->getBody0(); const btCollisionObject* colObj1 = manifold->getBody1(); diff --git a/src/esp/physics/bullet/BulletRigidObject.cpp b/src/esp/physics/bullet/BulletRigidObject.cpp index b2dd223308..bdfd2a1460 100644 --- a/src/esp/physics/bullet/BulletRigidObject.cpp +++ b/src/esp/physics/bullet/BulletRigidObject.cpp @@ -424,7 +424,7 @@ void BulletRigidObject::constructAndAddRigidBody(MotionType mt) { } std::string BulletRigidObject::getCollisionDebugName() { - return "RigidObject, " + initializationAttributes_->getHandle() + ", id " + + return "RigidObject, " + objInitAttributes_->getHandle() + ", id " + std::to_string(objectId_); } diff --git a/src/esp/physics/bullet/BulletURDFImporter.cpp b/src/esp/physics/bullet/BulletURDFImporter.cpp index b4c23e6758..8b584b41e9 100644 --- a/src/esp/physics/bullet/BulletURDFImporter.cpp +++ b/src/esp/physics/bullet/BulletURDFImporter.cpp @@ -194,8 +194,9 @@ void BulletURDFImporter::getAllIndices( int mbIndex = cache->getMbIndexFromUrdfIndex(urdfLinkIndex); cp.m_mbIndex = mbIndex; cp.m_parentIndex = parentIndex; - int parentMbIndex = - parentIndex >= 0 ? cache->getMbIndexFromUrdfIndex(parentIndex) : -1; + int parentMbIndex = parentIndex >= 0 + ? cache->getMbIndexFromUrdfIndex(parentIndex) + : BASELINK_ID; cp.m_parentMBIndex = parentMbIndex; allIndices.emplace_back(std::move(cp)); @@ -255,9 +256,8 @@ void BulletURDFImporter::initURDFToBulletCache( cache->m_urdfLinkIndices2BulletLinkIndices.resize( numTotalLinksIncludingBase); cache->m_urdfLinkLocalInertialFrames.resize(numTotalLinksIncludingBase); - - cache->m_currentMultiBodyLinkIndex = - -1; // multi body base has 'link' index -1 + // multi body base has 'link' index BASELINK_ID + cache->m_currentMultiBodyLinkIndex = BASELINK_ID; bool maintainLinkOrder = (flags & CUF_MAINTAIN_LINK_ORDER) != 0; if (maintainLinkOrder) { @@ -327,7 +327,7 @@ void BulletURDFImporter::convertURDFToBullet( parentTransforms[urdfLinkIndex] = parentTransformInWorldSpace; std::vector allIndices; - getAllIndices(urdfLinkIndex, -1, allIndices); + getAllIndices(urdfLinkIndex, BASELINK_ID, allIndices); std::sort(allIndices.begin(), allIndices.end(), [](const childParentIndex& a, const childParentIndex& b) { return a.m_index < b.m_index; diff --git a/src/esp/physics/bullet/BulletURDFImporter.h b/src/esp/physics/bullet/BulletURDFImporter.h index 7f37eb17f1..1e806f3fb4 100644 --- a/src/esp/physics/bullet/BulletURDFImporter.h +++ b/src/esp/physics/bullet/BulletURDFImporter.h @@ -54,7 +54,7 @@ struct URDFToBulletCached { std::vector m_urdfLinkIndices2BulletLinkIndices; std::vector m_urdfLinkLocalInertialFrames; - int m_currentMultiBodyLinkIndex{-1}; + int m_currentMultiBodyLinkIndex{BASELINK_ID}; class btMultiBody* m_bulletMultiBody{nullptr}; diff --git a/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp b/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp index 8a11e463b9..959d596eab 100644 --- a/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp +++ b/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp @@ -12,7 +12,8 @@ ArticulatedObjectManager::ArticulatedObjectManager() PhysicsObjectBaseManager("ArticulatedObject") { // build this manager's copy constructor map this->copyConstructorMap_["ManagedArticulatedObject"] = - &ArticulatedObjectManager::createObjectCopy; + &ArticulatedObjectManager::createObjCopyCtorMapEntry< + ManagedArticulatedObject>; // build the function pointers to proper wrapper construction methods, keyed // by the wrapper names @@ -21,7 +22,7 @@ ArticulatedObjectManager::ArticulatedObjectManager() ManagedArticulatedObject>; this->copyConstructorMap_["ManagedBulletArticulatedObject"] = - &ArticulatedObjectManager::createObjectCopy< + &ArticulatedObjectManager::createObjCopyCtorMapEntry< ManagedBulletArticulatedObject>; managedObjTypeConstructorMap_["ManagedBulletArticulatedObject"] = &ArticulatedObjectManager::createPhysicsObjectWrapper< diff --git a/src/esp/physics/objectManagers/RigidObjectManager.cpp b/src/esp/physics/objectManagers/RigidObjectManager.cpp index 27fdc0e00f..b106e4fd7e 100644 --- a/src/esp/physics/objectManagers/RigidObjectManager.cpp +++ b/src/esp/physics/objectManagers/RigidObjectManager.cpp @@ -12,7 +12,7 @@ RigidObjectManager::RigidObjectManager() // build this manager's copy constructor map, keyed by the type name of the // wrappers it will manage this->copyConstructorMap_["ManagedRigidObject"] = - &RigidObjectManager::createObjectCopy; + &RigidObjectManager::createObjCopyCtorMapEntry; // build the function pointers to proper wrapper construction methods, keyed // by the wrapper names @@ -20,7 +20,7 @@ RigidObjectManager::RigidObjectManager() &RigidObjectManager::createPhysicsObjectWrapper; this->copyConstructorMap_["ManagedBulletRigidObject"] = - &RigidObjectManager::createObjectCopy; + &RigidObjectManager::createObjCopyCtorMapEntry; managedObjTypeConstructorMap_["ManagedBulletRigidObject"] = &RigidObjectManager::createPhysicsObjectWrapper; } diff --git a/src/esp/physics/objectWrappers/ManagedArticulatedObject.h b/src/esp/physics/objectWrappers/ManagedArticulatedObject.h index c645531b20..608f577df1 100644 --- a/src/esp/physics/objectWrappers/ManagedArticulatedObject.h +++ b/src/esp/physics/objectWrappers/ManagedArticulatedObject.h @@ -48,7 +48,7 @@ class ManagedArticulatedObject return 1.0; } - scene::SceneNode* getLinkSceneNode(int linkId = -1) const { + scene::SceneNode* getLinkSceneNode(int linkId = BASELINK_ID) const { if (auto sp = getObjectReference()) { return &const_cast(sp->getLinkSceneNode(linkId)); } @@ -56,7 +56,7 @@ class ManagedArticulatedObject } std::vector getLinkVisualSceneNodes( - int linkId = -1) const { + int linkId = BASELINK_ID) const { if (auto sp = getObjectReference()) { return sp->getLinkVisualSceneNodes(linkId); } @@ -73,7 +73,7 @@ class ManagedArticulatedObject if (auto sp = getObjectReference()) { return sp->getNumLinks(); } - return -1; + return ID_UNDEFINED; } std::vector getLinkIds() const { @@ -94,7 +94,7 @@ class ManagedArticulatedObject if (auto sp = getObjectReference()) { return sp->getLinkIdFromName(_name); } - return -1; + return ID_UNDEFINED; } std::unordered_map getLinkObjectIds() const { @@ -237,7 +237,7 @@ class ManagedArticulatedObject if (auto sp = getObjectReference()) { return sp->getLinkDoFOffset(linkId); } - return -1; + return ID_UNDEFINED; } int getLinkNumDoFs(int linkId) const { @@ -251,7 +251,7 @@ class ManagedArticulatedObject if (auto sp = getObjectReference()) { return sp->getLinkJointPosOffset(linkId); } - return -1; + return ID_UNDEFINED; } int getLinkNumJointPos(int linkId) const { diff --git a/src/esp/sim/Simulator.cpp b/src/esp/sim/Simulator.cpp index 8f8dd01d5a..62cd613cd1 100644 --- a/src/esp/sim/Simulator.cpp +++ b/src/esp/sim/Simulator.cpp @@ -426,9 +426,9 @@ bool Simulator::createSceneInstance(const std::string& activeSceneName) { success = instanceArticulatedObjectsForSceneAttributes( curSceneInstanceAttributes_); if (success) { - // TODO : reset may eventually have all the scene instantiation code so - // that scenes can be reset - reset(); + // Pass true so that the object/AO placement code is bypassed in + // physicsManager_->reset + reset(true); } } } @@ -616,12 +616,6 @@ bool Simulator::instanceObjectsForSceneAttributes( // node to attach object to scene::SceneNode* attachmentNode = nullptr; - // whether or not to correct for COM shift - only do for blender-sourced - // scene attributes - bool defaultCOMCorrection = - (curSceneInstanceAttributes_->getTranslationOrigin() == - metadata::attributes::SceneInstanceTranslationOrigin::AssetLocal); - // Iterate through instances, create object and implement initial // transformation. for (const auto& objInst : objectInstances) { @@ -635,8 +629,8 @@ bool Simulator::instanceObjectsForSceneAttributes( config_.activeSceneName)); // objID = - physicsManager_->addObjectInstance(objInst, defaultCOMCorrection, - &getDrawableGroup(), attachmentNode, + physicsManager_->addObjectInstance(objInst, &getDrawableGroup(), + attachmentNode, config_.sceneLightSetupKey); } // for each object attributes return true; @@ -670,12 +664,12 @@ bool Simulator::instanceArticulatedObjectsForSceneAttributes( return true; } // Simulator::instanceArticulatedObjectsForSceneAttributes -void Simulator::reset() { +void Simulator::reset(bool calledAfterSceneCreate) { if (physicsManager_ != nullptr) { // Note: resets time to 0 and all existing objects set back to initial // states. Does not add back deleted objects or delete added objects. Does // not break ManagedObject pointers. - physicsManager_->reset(); + physicsManager_->reset(calledAfterSceneCreate); } for (auto& agent : agents_) { @@ -683,7 +677,7 @@ void Simulator::reset() { } getActiveSceneGraph().getRootNode().computeCumulativeBB(); resourceManager_->setLightSetup(gfx::getDefaultLights()); -} // Simulator::reset() +} // Simulator::reset metadata::attributes::SceneInstanceAttributes::ptr Simulator::buildCurrentStateSceneAttributes() const { diff --git a/src/esp/sim/Simulator.h b/src/esp/sim/Simulator.h index db435c1fba..f19bf6e639 100644 --- a/src/esp/sim/Simulator.h +++ b/src/esp/sim/Simulator.h @@ -75,8 +75,11 @@ class Simulator { * Does not invalidate existing ManagedObject wrappers. * Does not add or remove object instances. * Only changes motion_type when scene_instance specified a motion type. + * @param calledAfterSceneCreate Whether this reset is being called after a + * new scene has been created in reconfigure. If so we con't want to + * redundantly re-place the newly-placed object positions. */ - void reset(); + void reset(bool calledAfterSceneCreate = false); void seed(uint32_t newSeed); @@ -474,6 +477,21 @@ class Simulator { return curSceneInstanceAttributes_->getSimplifiedHandle(); } + /** + * @brief Return whether the @ref + * esp::metadata::attributes::SceneInstanceAttributes used to create the scene + * currently being simulated/displayed specifies a default COM handling for + * rigid objects + */ + + bool getCurSceneDefaultCOMHandling() const { + if (curSceneInstanceAttributes_ == nullptr) { + return false; + } + return (curSceneInstanceAttributes_->getTranslationOrigin() == + metadata::attributes::SceneInstanceTranslationOrigin::AssetLocal); + } + /** * @brief Set the gravity in a physical scene. */ diff --git a/src/tests/CMakeLists.txt b/src/tests/CMakeLists.txt index d276dee3af..7d7c7ae766 100644 --- a/src/tests/CMakeLists.txt +++ b/src/tests/CMakeLists.txt @@ -74,7 +74,7 @@ if(MagnumPlugins_KtxImageConverter_FOUND) target_link_libraries(GfxBatchRendererTest PRIVATE MagnumPlugins::KtxImageConverter) endif() -corrade_add_test(CoreTest CoreTest.cpp LIBRARIES core io) +corrade_add_test(ConfigurationTest ConfigurationTest.cpp LIBRARIES core io) corrade_add_test(CullingTest CullingTest.cpp LIBRARIES gfx) target_include_directories(CullingTest PRIVATE ${CMAKE_CURRENT_BINARY_DIR}) diff --git a/src/tests/ConfigurationTest.cpp b/src/tests/ConfigurationTest.cpp new file mode 100644 index 0000000000..29ca1ca979 --- /dev/null +++ b/src/tests/ConfigurationTest.cpp @@ -0,0 +1,589 @@ +// Copyright (c) Meta Platforms, Inc. and its affiliates. +// This source code is licensed under the MIT license found in the +// LICENSE file in the root directory of this source tree. + +#include +#include +#include +#include "esp/core/Configuration.h" +#include "esp/core/Esp.h" + +using namespace esp::core::config; +namespace Cr = Corrade; + +namespace { + +struct ConfigurationTest : Cr::TestSuite::Tester { + explicit ConfigurationTest(); + + /** + * @brief A Configuration is a hierarchical storage structure. This + * recursively builds a subconfiguration hierarchy within the passed @p config + * using the given values. + * @param countPerDepth Number of subconfigs to build for each depth layer. + * @param curDepth Current recursion depth. + * @param totalDepth Total recursion depth +1 == total subconfig hierarchy + * depth of given @p config counting base layer (add 1 because head + * recursion). + * @param config The Configuration in which to build the subconfig hierarchy. + */ + void buildSubconfigsInConfig(int countPerDepth, + int curDepth, + int totalDepth, + Configuration::ptr& config); + + /** + * @brief A Configuration is a hierarchical storage structure. This + * recursively verifies the passed @p config has the subconfig hierarchy + * structure as described by the given values. + * @param countPerDepth Number of subconfigs that should be preseent in each + * depth layer. + * @param curDepth Current recursion depth. + * @param totalDepth Total recursion depth +1 == total subconfig hierarchy + * depth of given @p config counting base layer (add 1 because head + * recursion). + * @param config The Configuration holding the subconfig hierarchy we are + * trying to verify. + */ + void verifySubconfigTree(int countPerDepth, + int curDepth, + int totalDepth, + Configuration::cptr& config) const; + + /** + * @brief Recursively add or modify the string value of the given key in every + * subconfig of @p config with the given value + */ + void addOrModSubconfigTreeVals(const std::string& key, + const std::string& val, + Configuration::ptr& config); + + /** + * @brief Recursively verify that the given key exists in every subconfig of + * @p config with the appropriately modified version of the given value. + */ + void verifySubconfigTreeVals(const std::string& key, + const std::string& val, + Configuration::cptr& config) const; + + /** + * @brief Verifies that the two passed Configurations hold identical + * subconfig hierarchies for both values and structure. + */ + void compareSubconfigs(Configuration::cptr& src, Configuration::cptr& target); + + /** + * @brief Basic test of Configuration functionality + */ + void TestConfiguration(); + + /** + * @brief Test Configuration comparisons between value types requiring fuzzy + * logic (i.e. doubles). All additional numeric types added in the future that + * require fuzzy comparison should have their fuzzy equality bounds tested + * here. + */ + void TestConfigurationFuzzyVals(); + + /** + * @brief Test Configuration find capability. Find returns a list of + * subconfiguration keys required to find a particular key + */ + void TestSubconfigFind(); + + /** + * @brief Test Configuration find, merge and edit capability. Builds + * subconfig hierarchy, finds a desired subconfig, duplicates and merges it + * with another and verifies results. + */ + void TestSubconfigFindAndMerge(); + + /** + * @brief Test Configuration subconfig filtering. Builds two identical + * subconfigs, modifies one such that it has changed values and also added + * values, then filters it using original copy and verifies that only + * new/different values remains. + */ + void TestSubconfigFilter(); + + esp::logging::LoggingContext loggingContext_; +}; // struct ConfigurationTest + +ConfigurationTest::ConfigurationTest() { + addTests({ + &ConfigurationTest::TestConfiguration, + &ConfigurationTest::TestConfigurationFuzzyVals, + &ConfigurationTest::TestSubconfigFind, + &ConfigurationTest::TestSubconfigFindAndMerge, + &ConfigurationTest::TestSubconfigFilter, + }); +} + +void ConfigurationTest::buildSubconfigsInConfig(int countPerDepth, + int curDepth, + int totalDepth, + Configuration::ptr& config) { + if (curDepth == totalDepth) { + return; + } + std::string breadcrumb = config->get("breadcrumb"); + for (int i = 0; i < countPerDepth; ++i) { + const std::string subconfigKey = Cr::Utility::formatString( + "breadcrumb_{}_depth_{}_subconfig_{}", breadcrumb, curDepth, i); + Configuration::ptr newCfg = + config->editSubconfig(subconfigKey); + // set the values within the new subconfig that describe the subconfig's + // status + newCfg->set("depth", curDepth); + newCfg->set("iter", i); + newCfg->set("breadcrumb", Cr::Utility::formatString("{}{}", breadcrumb, i)); + newCfg->set("key", subconfigKey); + + buildSubconfigsInConfig(countPerDepth, curDepth + 1, totalDepth, newCfg); + } +} // ConfigurationTest::buildSubconfigsInConfig + +void ConfigurationTest::verifySubconfigTree(int countPerDepth, + int curDepth, + int totalDepth, + Configuration::cptr& config) const { + if (curDepth == totalDepth) { + return; + } + std::string breadcrumb = config->get("breadcrumb"); + for (int i = 0; i < countPerDepth; ++i) { + const std::string subconfigKey = Cr::Utility::formatString( + "breadcrumb_{}_depth_{}_subconfig_{}", breadcrumb, curDepth, i); + // Verify subconfig with key exists + CORRADE_VERIFY(config->hasSubconfig(subconfigKey)); + Configuration::cptr newCfg = config->getSubconfigView(subconfigKey); + CORRADE_VERIFY(newCfg); + // Verify subconfig depth value is as expected + CORRADE_COMPARE(newCfg->get("depth"), curDepth); + // Verify iteration and parent iteration + CORRADE_COMPARE(newCfg->get("iter"), i); + CORRADE_COMPARE(newCfg->get("breadcrumb"), + Cr::Utility::formatString("{}{}", breadcrumb, i)); + CORRADE_COMPARE(newCfg->get("key"), subconfigKey); + // Check into tree + verifySubconfigTree(countPerDepth, curDepth + 1, totalDepth, newCfg); + } + CORRADE_COMPARE(config->getNumSubconfigs(), countPerDepth); + +} // ConfigurationTest::verifySubconfigTree + +void ConfigurationTest::compareSubconfigs(Configuration::cptr& src, + Configuration::cptr& target) { + // verify target has at least as many subconfigs that src has + CORRADE_VERIFY(src->getNumSubconfigs() <= target->getNumSubconfigs()); + // verify that target has all the values that src has, and they are equal. + auto srcIterValPair = src->getValuesIterator(); + for (auto& cfgIter = srcIterValPair.first; cfgIter != srcIterValPair.second; + ++cfgIter) { + CORRADE_VERIFY(cfgIter->second == target->get(cfgIter->first)); + } + + // Verify all subconfigs have the same keys - get begin/end iterators for src + // subconfigs + auto srcIterConfigPair = src->getSubconfigIterator(); + for (auto& cfgIter = srcIterConfigPair.first; + cfgIter != srcIterConfigPair.second; ++cfgIter) { + CORRADE_VERIFY(target->hasSubconfig(cfgIter->first)); + Configuration::cptr srcSubConfig = cfgIter->second; + Configuration::cptr tarSubConfig = target->getSubconfigView(cfgIter->first); + compareSubconfigs(srcSubConfig, tarSubConfig); + } + +} // ConfigurationTest::compareSubconfigs + +void ConfigurationTest::addOrModSubconfigTreeVals(const std::string& key, + const std::string& val, + Configuration::ptr& config) { + std::string newVal = val; + if (config->hasKeyToValOfType(key, + esp::core::config::ConfigValType::String)) { + newVal = + Cr::Utility::formatString("{}_{}", config->get(key), val); + } + config->set(key, newVal); + auto cfgIterPair = config->getSubconfigIterator(); + // Get subconfig keys + const auto& subsetKeys = config->getSubconfigKeys(); + for (const auto& subKey : subsetKeys) { + auto subconfig = config->editSubconfig(subKey); + addOrModSubconfigTreeVals(key, val, subconfig); + } +} // ConfigurationTest::addOrModSubconfigTreeVals + +void ConfigurationTest::verifySubconfigTreeVals( + const std::string& key, + const std::string& val, + Configuration::cptr& config) const { + CORRADE_VERIFY( + config->hasKeyToValOfType(key, esp::core::config::ConfigValType::String)); + std::string testVal = config->get(key); + std::size_t foundLoc = testVal.find(val); + CORRADE_VERIFY(foundLoc != std::string::npos); + auto srcIterConfigPair = config->getSubconfigIterator(); + for (auto& cfgIter = srcIterConfigPair.first; + cfgIter != srcIterConfigPair.second; ++cfgIter) { + Configuration::cptr subCfg = cfgIter->second; + verifySubconfigTreeVals(key, val, subCfg); + } +} // ConfigurationTest::verifySubconfigTreeVals + +void ConfigurationTest::TestConfiguration() { + Configuration cfg; + cfg.set("myBool", true); + cfg.set("myInt", 10); + cfg.set("myFloatToDouble", 1.2f); + cfg.set("myVec2", Mn::Vector2{1.0, 2.0}); + cfg.set("myVec3", Mn::Vector3{1.0, 2.0, 3.0}); + cfg.set("myVec4", Mn::Vector4{1.0, 2.0, 3.0, 4.0}); + cfg.set("myQuat", Mn::Quaternion{{1.0, 2.0, 3.0}, 0.1}); + cfg.set("myMat3", Mn::Matrix3(Mn::Math::IdentityInit)); + cfg.set("myMat4", Mn::Matrix4(Mn::Math::IdentityInit)); + cfg.set("myRad", Mn::Rad{1.23}); + cfg.set("myString", "test"); + + CORRADE_VERIFY(cfg.hasValue("myBool")); + CORRADE_VERIFY(cfg.hasValue("myInt")); + CORRADE_VERIFY(cfg.hasValue("myFloatToDouble")); + CORRADE_VERIFY(cfg.hasValue("myVec2")); + CORRADE_VERIFY(cfg.hasValue("myVec3")); + CORRADE_VERIFY(cfg.hasValue("myMat3")); + CORRADE_VERIFY(cfg.hasValue("myVec4")); + CORRADE_VERIFY(cfg.hasValue("myQuat")); + CORRADE_VERIFY(cfg.hasValue("myMat3")); + CORRADE_VERIFY(cfg.hasValue("myRad")); + CORRADE_VERIFY(cfg.hasValue("myString")); + + CORRADE_COMPARE(cfg.get("myBool"), true); + CORRADE_COMPARE(cfg.get("myInt"), 10); + CORRADE_COMPARE(cfg.get("myFloatToDouble"), 1.2f); + CORRADE_COMPARE(cfg.get("myVec2"), Mn::Vector2(1.0, 2.0)); + CORRADE_COMPARE(cfg.get("myVec3"), Mn::Vector3(1.0, 2.0, 3.0)); + CORRADE_COMPARE(cfg.get("myVec4"), + Mn::Vector4(1.0, 2.0, 3.0, 4.0)); + CORRADE_COMPARE(cfg.get("myQuat"), + Mn::Quaternion({1.0, 2.0, 3.0}, 0.1)); + CORRADE_COMPARE(cfg.get("myRad"), Mn::Rad(1.23)); + + for (int i = 0; i < 3; ++i) { + CORRADE_COMPARE(cfg.get("myMat3").row(i)[i], 1); + } + for (int i = 0; i < 4; ++i) { + CORRADE_COMPARE(cfg.get("myMat4").row(i)[i], 1); + } + + CORRADE_COMPARE(cfg.get("myString"), "test"); +} // ConfigurationTest::TestConfiguration test + +void ConfigurationTest::TestConfigurationFuzzyVals() { + Configuration cfg; + + // Specify values to test + cfg.set("fuzzyTestVal0", 1.0); + cfg.set("fuzzyTestVal1", 1.0 + Mn::Math::TypeTraits::epsilon() / 2); + // Scale the epsilon to be too big to be seen as the same. + cfg.set("fuzzyTestVal2", 1.0 + Mn::Math::TypeTraits::epsilon() * 4); + + CORRADE_VERIFY(cfg.hasValue("fuzzyTestVal0")); + CORRADE_VERIFY(cfg.hasValue("fuzzyTestVal1")); + CORRADE_VERIFY(cfg.hasValue("fuzzyTestVal2")); + // Verify very close doubles are considered sufficiently close by fuzzy + // compare + CORRADE_COMPARE(cfg.get("fuzzyTestVal0"), cfg.get("fuzzyTestVal1")); + + // verify very close but not-quite-close enough doubles are considered + // different by magnum's fuzzy compare + CORRADE_COMPARE_AS(cfg.get("fuzzyTestVal0"), cfg.get("fuzzyTestVal2"), + Cr::TestSuite::Compare::NotEqual); + +} // ConfigurationTest::TestConfigurationFuzzyVals + +// Test configuration find functionality +void ConfigurationTest::TestSubconfigFind() { + Configuration::ptr cfg = Configuration::create(); + Configuration::ptr baseCfg = cfg; + // Build layers of subconfigs + for (int i = 0; i < 10; ++i) { + Configuration::ptr newCfg = cfg->editSubconfig( + Cr::Utility::formatString("depth_{}_subconfig_{}", i + 1, i)); + newCfg->set("depth", i + 1); + cfg = newCfg; + } + // Set deepest layer config to have treasure + cfg->set("treasure", "this is the treasure!"); + // Find the treasure! + std::vector keyList = baseCfg->findValue("treasure"); + + // Display breadcrumbs + std::string resStr = Cr::Utility::formatString( + "Vector of 'treasure' keys is size : {}", keyList.size()); + for (const auto& key : keyList) { + Cr::Utility::formatInto(resStr, resStr.size(), "\n\t{}", key); + } + ESP_DEBUG() << resStr; + // Verify the found treasure + CORRADE_COMPARE(keyList.size(), 11); + + Configuration::cptr viewConfig = baseCfg; + for (int i = 0; i < 10; ++i) { + const std::string subconfigKey = + Cr::Utility::formatString("depth_{}_subconfig_{}", i + 1, i); + CORRADE_COMPARE(keyList[i], subconfigKey); + // Verify that subconfig with given name exists + CORRADE_VERIFY(viewConfig->hasSubconfig(subconfigKey)); + // retrieve actual subconfig + Configuration::cptr newCfg = viewConfig->getSubconfigView(subconfigKey); + // verity subconfig has correct depth value + CORRADE_COMPARE(newCfg->get("depth"), i + 1); + viewConfig = newCfg; + } + CORRADE_VERIFY(viewConfig->hasValue("treasure")); + CORRADE_COMPARE(viewConfig->get("treasure"), + "this is the treasure!"); + + // Verify pirate isn't found + std::vector notFoundKeyList = baseCfg->findValue("pirate"); + CORRADE_COMPARE(notFoundKeyList.size(), 0); +} + +// Test subconfig edit/merge and save +void ConfigurationTest::TestSubconfigFindAndMerge() { + Configuration::ptr cfg = Configuration::create(); + CORRADE_VERIFY(cfg); + // Set base value for parent iteration + cfg->set("breadcrumb", ""); + int depthPlus1 = 5; + int count = 3; + // Build subconfig tree 4 levels deep, 3 subconfigs per config + buildSubconfigsInConfig(count, 0, depthPlus1, cfg); + Configuration::cptr const_cfg = + std::const_pointer_cast(cfg); + // Verify subconfig tree structure using const views + verifySubconfigTree(count, 0, depthPlus1, const_cfg); + + // grab a subconfig, edit it and save it with a different key + // use find to get key path + const std::string keyToFind = "breadcrumb_212_depth_3_subconfig_2"; + // Find breadcrumb path of keys into subconfigs that lead to keyToFind + std::vector subconfigKeyPath = cfg->findValue(keyToFind); + // Display breadcrumbs + std::string resStr = Cr::Utility::formatString( + "Vector of desired subconfig keys to get to '{}' " + "subconfig is size : {}", + keyToFind, subconfigKeyPath.size()); + for (const auto& key : subconfigKeyPath) { + Cr::Utility::formatInto(resStr, resStr.size(), "\n\t{}", key); + } + ESP_DEBUG() << resStr; + // Verify there are 4 layers of subconfigs to keyToFind + CORRADE_COMPARE(subconfigKeyPath.size(), 4); + // Verify the last entry holds keyToFind + CORRADE_COMPARE(subconfigKeyPath[3], keyToFind); + // Procede through the subconfig layers and find the desired target config + Configuration::cptr viewConfig = cfg; + Configuration::cptr lastConfig = cfg; + for (const std::string& key : subconfigKeyPath) { + Configuration::cptr tempConfig = viewConfig->getSubconfigView(key); + CORRADE_COMPARE(tempConfig->get("key"), key); + lastConfig = viewConfig; + viewConfig = tempConfig; + } + + // By here lastConfig is the parent of viewConfig, the config we want at + // keyToFind + // We make a copy of viewConfig and verify the copy has the same values as the + // original + Configuration::ptr cfgToEdit = + lastConfig->getSubconfigCopy(keyToFind); + CORRADE_VERIFY(*cfgToEdit == *viewConfig); + // Now modify new subconfig copy and verify the original viewConfig is not + // also modified + const std::string newKey = "edited_subconfig"; + cfgToEdit->set("key", newKey); + cfgToEdit->set("depth", 0); + cfgToEdit->set("breadcrumb", ""); + cfgToEdit->set("test_string", "this is an added test string"); + + // Added edited subconfig to base config (top of hierarchy) + cfg->setSubconfigPtr(newKey, cfgToEdit); + CORRADE_VERIFY(cfg->hasSubconfig(newKey)); + // Get an immutable view of this subconfig and verify the data it holds + Configuration::cptr cfgToVerify = cfg->getSubconfigView(newKey); + CORRADE_COMPARE(cfgToVerify->get("breadcrumb"), ""); + CORRADE_COMPARE(cfgToVerify->get("test_string"), + "this is an added test string"); + CORRADE_COMPARE(cfgToVerify->get("key"), newKey); + CORRADE_COMPARE(cfgToVerify->get("depth"), 0); + // Make sure original was not modified + CORRADE_VERIFY(viewConfig->get("breadcrumb") != ""); + CORRADE_VERIFY(viewConfig->get("key") != newKey); + CORRADE_VERIFY(viewConfig->get("depth") != 0); + CORRADE_VERIFY(!viewConfig->hasValue("test_string")); + + // Now Test merge/Overwriting + const std::string mergedKey = "merged_subconfig"; + Configuration::ptr cfgToOverwrite = + cfg->editSubconfig(mergedKey); + + // first set some test values that will be clobbered + cfgToOverwrite->set("key", mergedKey); + cfgToOverwrite->set("depth", 11); + cfgToOverwrite->set("breadcrumb", "1123"); + cfgToOverwrite->set("test_string", "this string will be clobbered"); + // Now add some values that won't be clobbered + cfgToOverwrite->set("myBool", true); + cfgToOverwrite->set("myInt", 10); + cfgToOverwrite->set("myFloatToDouble", 1.2f); + cfgToOverwrite->set("myVec2", Mn::Vector2{1.0, 2.0}); + cfgToOverwrite->set("myVec3", Mn::Vector3{1.0, 2.0, 3.0}); + cfgToOverwrite->set("myVec4", Mn::Vector4{1.0, 2.0, 3.0, 4.0}); + cfgToOverwrite->set("myQuat", Mn::Quaternion{{1.0, 2.0, 3.0}, 0.1}); + cfgToOverwrite->set("myRad", Mn::Rad{1.23}); + cfgToOverwrite->set("myString", "test"); + + // Now overwrite the values from cfgToVerify + cfgToOverwrite->overwriteWithConfig(cfgToVerify); + + CORRADE_VERIFY(cfg->hasSubconfig(mergedKey)); + // Verify all the overwritten values are correct + Configuration::cptr cfgToVerifyOverwrite = cfg->getSubconfigView(mergedKey); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("breadcrumb"), ""); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("test_string"), + "this is an added test string"); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("key"), newKey); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("depth"), 0); + // Verify original non-overwritten values are still present + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myBool"), true); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myInt"), 10); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myFloatToDouble"), 1.2f); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myVec2"), + Mn::Vector2(1.0, 2.0)); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myVec3"), + Mn::Vector3(1.0, 2.0, 3.0)); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myVec4"), + Mn::Vector4(1.0, 2.0, 3.0, 4.0)); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myQuat"), + Mn::Quaternion({1.0, 2.0, 3.0}, 0.1)); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myRad"), Mn::Rad(1.23)); + CORRADE_COMPARE(cfgToVerifyOverwrite->get("myString"), "test"); + // Verify overwrite performed properly + compareSubconfigs(cfgToVerify, cfgToVerifyOverwrite); +} + +void ConfigurationTest::TestSubconfigFilter() { + Configuration::ptr cfg = Configuration::create(); + CORRADE_VERIFY(cfg); + // Build and verify hierarchy + int depthPlus1 = 5; + int count = 3; + // build two identical subconfigs and place within base Configuration + const std::string filterKey = "cfgToFilterBy"; + // Get actual subconfig + Configuration::ptr cfgToFilterBy = + cfg->editSubconfig(filterKey); + // add some root values will be present in 'modified' subconfig too + cfgToFilterBy->set("baseStrKey", "filterKey"); + cfgToFilterBy->set("baseIntKey", 1); + cfgToFilterBy->set("baseBoolKey", true); + cfgToFilterBy->set("baseDoubleKey", 3.14); + cfgToFilterBy->set("baseStrKeyToMod", "modFilterKey"); + cfgToFilterBy->set("baseIntKeyToMod", 11); + cfgToFilterBy->set("baseBoolKeyToMod", true); + cfgToFilterBy->set("baseDoubleKeyToMod", 2.718); + // Build subconfig tree 4 levels deep, 3 subconfigs per config + buildSubconfigsInConfig(count, 0, depthPlus1, cfgToFilterBy); + + const std::string modKey = "modifiedSubconfig"; + // get copy of original filter config + Configuration::ptr cfgToModify = + cfg->getSubconfigCopy(filterKey); + // move copy into cfg + cfg->setSubconfigPtr(modKey, cfgToModify); + // retrieve pointer to new copy + cfgToModify = cfg->editSubconfig(modKey); + + // Build subconfig tree 4 levels deep, 3 subconfigs per config + buildSubconfigsInConfig(count, 0, depthPlus1, cfgToModify); + + // compare both configs and verify they are equal + { + Configuration::cptr baseCompareCfg = + std::static_pointer_cast(cfgToFilterBy); + Configuration::cptr modCompareCfg = + std::static_pointer_cast(cfgToModify); + // verify both subconfigs are the same + compareSubconfigs(baseCompareCfg, modCompareCfg); + } + + // modify and save appropriate subconfig, filter using base subconfig, and + // then verify expected results + // Modify values that are also present in cfgToFilterBy + cfgToModify->set("baseStrKeyToMod", "_modified"); + cfgToModify->set("baseIntKeyToMod", 111); + cfgToModify->set("baseBoolKeyToMod", false); + cfgToModify->set("baseDoubleKeyToMod", 1234.5); + // Add 'mod' string to end of each config's breadcrumb string + addOrModSubconfigTreeVals("breadcrumb", "mod", cfgToModify); + // Add new string to each config + addOrModSubconfigTreeVals("newStrValue", "new string", cfgToModify); + // Add values that are not present in cfgToFilterBy + cfgToModify->set("myBool", true); + cfgToModify->set("myInt", 10); + cfgToModify->set("myFloatToDouble", 1.2f); + cfgToModify->set("myVec2", Mn::Vector2{1.0, 2.0}); + cfgToModify->set("myVec3", Mn::Vector3{1.0, 2.0, 3.0}); + cfgToModify->set("myVec4", Mn::Vector4{1.0, 2.0, 3.0, 4.0}); + cfgToModify->set("myQuat", Mn::Quaternion{{1.0, 2.0, 3.0}, 0.1}); + cfgToModify->set("myRad", Mn::Rad{1.23}); + cfgToModify->set("myString", "test"); + + // Now filter the config to not have any data shared ith cfgToFilterBy + cfgToModify->filterFromConfig(cfgToFilterBy); + // Verify old shared values are gone + CORRADE_VERIFY(!cfgToModify->hasValue("baseStrKey")); + CORRADE_VERIFY(!cfgToModify->hasValue("baseIntKey")); + CORRADE_VERIFY(!cfgToModify->hasValue("baseBoolKey")); + CORRADE_VERIFY(!cfgToModify->hasValue("baseDoubleKey")); + + // Verify modified shared values are present + CORRADE_VERIFY(cfgToModify->hasValue("baseStrKeyToMod")); + CORRADE_VERIFY(cfgToModify->hasValue("baseIntKeyToMod")); + CORRADE_VERIFY(cfgToModify->hasValue("baseBoolKeyToMod")); + CORRADE_VERIFY(cfgToModify->hasValue("baseDoubleKeyToMod")); + // ...and have expected values + CORRADE_COMPARE(cfgToModify->get("baseStrKeyToMod"), + "_modified"); + CORRADE_COMPARE(cfgToModify->get("baseIntKeyToMod"), 111); + CORRADE_COMPARE(cfgToModify->get("baseBoolKeyToMod"), false); + CORRADE_COMPARE(cfgToModify->get("baseDoubleKeyToMod"), 1234.5); + + // Verify modified values still present + CORRADE_COMPARE(cfgToModify->get("myBool"), true); + CORRADE_COMPARE(cfgToModify->get("myInt"), 10); + CORRADE_COMPARE(cfgToModify->get("myFloatToDouble"), 1.2f); + CORRADE_COMPARE(cfgToModify->get("myVec2"), + Mn::Vector2(1.0, 2.0)); + CORRADE_COMPARE(cfgToModify->get("myVec3"), + Mn::Vector3(1.0, 2.0, 3.0)); + CORRADE_COMPARE(cfgToModify->get("myVec4"), + Mn::Vector4(1.0, 2.0, 3.0, 4.0)); + CORRADE_COMPARE(cfgToModify->get("myQuat"), + Mn::Quaternion({1.0, 2.0, 3.0}, 0.1)); + CORRADE_COMPARE(cfgToModify->get("myRad"), Mn::Rad(1.23)); + CORRADE_COMPARE(cfgToModify->get("myString"), "test"); + + Configuration::cptr constModCfg = + std::const_pointer_cast(cfgToModify); + // verify breadcrumb mod is present + verifySubconfigTreeVals("breadcrumb", "mod", constModCfg); + // verify newStrValue is present + verifySubconfigTreeVals("newStrValue", "new string", constModCfg); +} // ConfigurationTest::TestSubconfigFilter + +} // namespace + +CORRADE_TEST_MAIN(ConfigurationTest) diff --git a/src/tests/CoreTest.cpp b/src/tests/CoreTest.cpp deleted file mode 100644 index 2bef3e8a99..0000000000 --- a/src/tests/CoreTest.cpp +++ /dev/null @@ -1,334 +0,0 @@ -// Copyright (c) Meta Platforms, Inc. and its affiliates. -// This source code is licensed under the MIT license found in the -// LICENSE file in the root directory of this source tree. - -#include -#include -#include "esp/core/Configuration.h" -#include "esp/core/Esp.h" - -using namespace esp::core::config; -namespace Cr = Corrade; - -namespace { - -struct CoreTest : Cr::TestSuite::Tester { - explicit CoreTest(); - - void buildSubconfigsInConfig(int countPerDepth, - int curDepth, - int totalDepth, - Configuration::ptr& config); - - void verifySubconfigTree(int countPerDepth, - int curDepth, - int totalDepth, - Configuration::cptr& config); - - void compareSubconfigs(Configuration::cptr& src, Configuration::cptr& target); - - void TestConfiguration(); - - /** - * @brief Test Configuration find and subconfig edit capability. Find returns - * a list of subconfiguration keys required to find a particular key - */ - void TestConfigurationSubconfigFind(); - - esp::logging::LoggingContext loggingContext_; -}; // struct CoreTest - -CoreTest::CoreTest() { - addTests({ - &CoreTest::TestConfiguration, - &CoreTest::TestConfigurationSubconfigFind, - }); -} - -void CoreTest::buildSubconfigsInConfig(int countPerDepth, - int curDepth, - int totalDepth, - Configuration::ptr& config) { - if (curDepth == totalDepth) { - return; - } - std::string breadcrumb = config->get("breakcrumb"); - for (int i = 0; i < countPerDepth; ++i) { - const std::string subconfigKey = Cr::Utility::formatString( - "breadcrumb_{}_depth_{}_subconfig_{}", breadcrumb, curDepth, i); - Configuration::ptr newCfg = - config->editSubconfig(subconfigKey); - newCfg->set("depth", curDepth); - newCfg->set("iter", i); - newCfg->set("breakcrumb", Cr::Utility::formatString("{}{}", breadcrumb, i)); - newCfg->set("key", subconfigKey); - - buildSubconfigsInConfig(countPerDepth, curDepth + 1, totalDepth, newCfg); - } -} // CoreTest::buildSubconfigsInConfig - -void CoreTest::verifySubconfigTree(int countPerDepth, - int curDepth, - int totalDepth, - Configuration::cptr& config) { - if (curDepth == totalDepth) { - return; - } - std::string breadcrumb = config->get("breakcrumb"); - for (int i = 0; i < countPerDepth; ++i) { - const std::string subconfigKey = Cr::Utility::formatString( - "breadcrumb_{}_depth_{}_subconfig_{}", breadcrumb, curDepth, i); - // Verify subconfig with key exists - CORRADE_VERIFY(config->hasSubconfig(subconfigKey)); - Configuration::cptr newCfg = config->getSubconfigView(subconfigKey); - CORRADE_VERIFY(newCfg); - // Verify subconfig depth value is as expected - CORRADE_COMPARE(newCfg->get("depth"), curDepth); - // Verify iteration and parent iteration - CORRADE_COMPARE(newCfg->get("iter"), i); - CORRADE_COMPARE(newCfg->get("breakcrumb"), - Cr::Utility::formatString("{}{}", breadcrumb, i)); - CORRADE_COMPARE(newCfg->get("key"), subconfigKey); - // Check into tree - verifySubconfigTree(countPerDepth, curDepth + 1, totalDepth, newCfg); - } - CORRADE_COMPARE(config->getNumSubconfigs(), countPerDepth); - -} // CoreTest::verifySubconfigTree - -void CoreTest::compareSubconfigs(Configuration::cptr& src, - Configuration::cptr& target) { - // verify target has at least all the number of subconfigs that src has - CORRADE_VERIFY(src->getNumSubconfigs() <= target->getNumSubconfigs()); - // verify that target has all the values that src has, and they are equal. - auto srcIterValPair = src->getValuesIterator(); - for (auto& cfgIter = srcIterValPair.first; cfgIter != srcIterValPair.second; - ++cfgIter) { - CORRADE_VERIFY(cfgIter->second == target->get(cfgIter->first)); - } - - // Verify all subconfigs have the same keys - get begin/end iterators for src - // subconfigs - auto srcIterConfigPair = src->getSubconfigIterator(); - for (auto& cfgIter = srcIterConfigPair.first; - cfgIter != srcIterConfigPair.second; ++cfgIter) { - CORRADE_VERIFY(target->hasSubconfig(cfgIter->first)); - Configuration::cptr srcSubConfig = cfgIter->second; - Configuration::cptr tarSubConfig = target->getSubconfigView(cfgIter->first); - compareSubconfigs(srcSubConfig, tarSubConfig); - } - -} // CoreTest::compareSubconfigs - -void CoreTest::TestConfiguration() { - Configuration cfg; - cfg.set("myBool", true); - cfg.set("myInt", 10); - cfg.set("myFloatToDouble", 1.2f); - cfg.set("myVec2", Mn::Vector2{1.0, 2.0}); - cfg.set("myVec3", Mn::Vector3{1.0, 2.0, 3.0}); - cfg.set("myVec4", Mn::Vector4{1.0, 2.0, 3.0, 4.0}); - cfg.set("myQuat", Mn::Quaternion{{1.0, 2.0, 3.0}, 0.1}); - cfg.set("myMat3", Mn::Matrix3(Mn::Math::IdentityInit)); - cfg.set("myMat4", Mn::Matrix4(Mn::Math::IdentityInit)); - cfg.set("myRad", Mn::Rad{1.23}); - cfg.set("myString", "test"); - - CORRADE_VERIFY(cfg.hasValue("myBool")); - CORRADE_VERIFY(cfg.hasValue("myInt")); - CORRADE_VERIFY(cfg.hasValue("myFloatToDouble")); - CORRADE_VERIFY(cfg.hasValue("myVec2")); - CORRADE_VERIFY(cfg.hasValue("myVec3")); - CORRADE_VERIFY(cfg.hasValue("myMat3")); - CORRADE_VERIFY(cfg.hasValue("myVec4")); - CORRADE_VERIFY(cfg.hasValue("myQuat")); - CORRADE_VERIFY(cfg.hasValue("myMat3")); - CORRADE_VERIFY(cfg.hasValue("myRad")); - CORRADE_VERIFY(cfg.hasValue("myString")); - - CORRADE_COMPARE(cfg.get("myBool"), true); - CORRADE_COMPARE(cfg.get("myInt"), 10); - CORRADE_COMPARE(cfg.get("myFloatToDouble"), 1.2f); - CORRADE_COMPARE(cfg.get("myVec2"), Mn::Vector2(1.0, 2.0)); - CORRADE_COMPARE(cfg.get("myVec3"), Mn::Vector3(1.0, 2.0, 3.0)); - CORRADE_COMPARE(cfg.get("myVec4"), - Mn::Vector4(1.0, 2.0, 3.0, 4.0)); - CORRADE_COMPARE(cfg.get("myQuat"), - Mn::Quaternion({1.0, 2.0, 3.0}, 0.1)); - CORRADE_COMPARE(cfg.get("myRad"), Mn::Rad(1.23)); - - for (int i = 0; i < 3; ++i) { - CORRADE_COMPARE(cfg.get("myMat3").row(i)[i], 1); - } - for (int i = 0; i < 4; ++i) { - CORRADE_COMPARE(cfg.get("myMat4").row(i)[i], 1); - } - - CORRADE_COMPARE(cfg.get("myString"), "test"); -} // CoreTest::TestConfiguration test - -// Test configuration find functionality -void CoreTest::TestConfigurationSubconfigFind() { - { - Configuration::ptr cfg = Configuration::create(); - Configuration::ptr baseCfg = cfg; - // Build layers of subconfigs - for (int i = 0; i < 10; ++i) { - Configuration::ptr newCfg = cfg->editSubconfig( - Cr::Utility::formatString("depth_{}_subconfig_{}", i + 1, i)); - newCfg->set("depth", i + 1); - cfg = newCfg; - } - // Set deepest layer config to have treasure - cfg->set("treasure", "this is the treasure!"); - // Find the treasure! - std::vector keyList = baseCfg->findValue("treasure"); - - // Display breadcrumbs - std::string resStr = Cr::Utility::formatString( - "Vector of 'treasure' keys is size : {}", keyList.size()); - for (const auto& key : keyList) { - Cr::Utility::formatInto(resStr, resStr.size(), "\n\t{}", key); - } - ESP_DEBUG() << resStr; - // Verify the found treasure - CORRADE_COMPARE(keyList.size(), 11); - - Configuration::cptr viewConfig = baseCfg; - for (int i = 0; i < 10; ++i) { - const std::string subconfigKey = - Cr::Utility::formatString("depth_{}_subconfig_{}", i + 1, i); - CORRADE_COMPARE(keyList[i], subconfigKey); - // Verify that subconfig with given name exists - CORRADE_VERIFY(viewConfig->hasSubconfig(subconfigKey)); - // retrieve actual subconfig - Configuration::cptr newCfg = viewConfig->getSubconfigView(subconfigKey); - // verity subconfig has correct depth value - CORRADE_COMPARE(newCfg->get("depth"), i + 1); - viewConfig = newCfg; - } - CORRADE_VERIFY(viewConfig->hasValue("treasure")); - CORRADE_COMPARE(viewConfig->get("treasure"), - "this is the treasure!"); - - // Verify pirate isn't found - std::vector notFoundKeyList = baseCfg->findValue("pirate"); - CORRADE_COMPARE(notFoundKeyList.size(), 0); - } - // Test subconfig edit/merge and save - { - Configuration::ptr cfg = Configuration::create(); - CORRADE_VERIFY(cfg); - // Set base value for parent iteration - cfg->set("breakcrumb", ""); - int depth = 5; - int count = 3; - // Build subconfig tree 4 levels deep, 3 subconfigs per config - buildSubconfigsInConfig(count, 0, depth, cfg); - Configuration::cptr const_cfg = - std::const_pointer_cast(cfg); - // Verify subconfig tree structure using const views - verifySubconfigTree(count, 0, depth, const_cfg); - - // grab a subconfig, edit it and save it with a different key - // use find to get key path - const std::string keyToFind = "breadcrumb_212_depth_3_subconfig_2"; - std::vector subconfigPath = cfg->findValue(keyToFind); - // Display breadcrumbs - std::string resStr = Cr::Utility::formatString( - "Vector of desired subconfig keys to get to '{}' " - "subconfig is size : {}", - keyToFind, subconfigPath.size()); - for (const auto& key : subconfigPath) { - Cr::Utility::formatInto(resStr, resStr.size(), "\n\t{}", key); - } - ESP_DEBUG() << resStr; - CORRADE_COMPARE(subconfigPath.size(), 4); - CORRADE_COMPARE(subconfigPath[3], keyToFind); - Configuration::cptr viewConfig = cfg; - Configuration::cptr lastConfig = cfg; - for (const std::string& key : subconfigPath) { - Configuration::cptr tempConfig = viewConfig->getSubconfigView(key); - CORRADE_COMPARE(tempConfig->get("key"), key); - lastConfig = viewConfig; - viewConfig = tempConfig; - } - // By here lastConfig is the parent of the config we want, and viewConfig is - // the config we are getting a copy of. - Configuration::ptr cfgToEdit = - lastConfig->getSubconfigCopy(keyToFind); - const std::string newKey = "edited_subconfig"; - cfgToEdit->set("key", newKey); - cfgToEdit->set("depth", 0); - cfgToEdit->set("breakcrumb", ""); - cfgToEdit->set("test_string", "this is an added test string"); - // Added edited subconfig to base config - cfg->setSubconfigPtr(newKey, cfgToEdit); - CORRADE_VERIFY(cfg->hasSubconfig(newKey)); - Configuration::cptr cfgToVerify = cfg->getSubconfigView(newKey); - CORRADE_COMPARE(cfgToVerify->get("breakcrumb"), ""); - CORRADE_COMPARE(cfgToVerify->get("test_string"), - "this is an added test string"); - CORRADE_COMPARE(cfgToVerify->get("key"), newKey); - CORRADE_COMPARE(cfgToVerify->get("depth"), 0); - // Make sure original was not modified - CORRADE_VERIFY(viewConfig->get("breakcrumb") != ""); - CORRADE_VERIFY(viewConfig->get("key") != newKey); - CORRADE_VERIFY(viewConfig->get("depth") != 0); - CORRADE_VERIFY(!viewConfig->hasValue("test_string")); - - // Now Test merge/Overwriting - const std::string mergedKey = "merged_subconfig"; - Configuration::ptr cfgToOverwrite = - cfg->editSubconfig(mergedKey); - - // first set some test values that will be clobbered - cfgToOverwrite->set("key", mergedKey); - cfgToOverwrite->set("depth", 11); - cfgToOverwrite->set("breakcrumb", "1123"); - cfgToOverwrite->set("test_string", "this string will be clobbered"); - // Now add some values that won't be clobbered - cfgToOverwrite->set("myBool", true); - cfgToOverwrite->set("myInt", 10); - cfgToOverwrite->set("myFloatToDouble", 1.2f); - cfgToOverwrite->set("myVec2", Mn::Vector2{1.0, 2.0}); - cfgToOverwrite->set("myVec3", Mn::Vector3{1.0, 2.0, 3.0}); - cfgToOverwrite->set("myVec4", Mn::Vector4{1.0, 2.0, 3.0, 4.0}); - cfgToOverwrite->set("myQuat", Mn::Quaternion{{1.0, 2.0, 3.0}, 0.1}); - cfgToOverwrite->set("myRad", Mn::Rad{1.23}); - cfgToOverwrite->set("myString", "test"); - - // Now overwrite the values from cfgToVerify - cfgToOverwrite->overwriteWithConfig(cfgToVerify); - - CORRADE_VERIFY(cfg->hasSubconfig(mergedKey)); - // Verify all the overwritten values are correct - Configuration::cptr cfgToVerifyOverwrite = cfg->getSubconfigView(mergedKey); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("breakcrumb"), ""); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("test_string"), - "this is an added test string"); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("key"), newKey); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("depth"), 0); - // Verify original non-overwritten values are still present - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myBool"), true); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myInt"), 10); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myFloatToDouble"), 1.2f); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myVec2"), - Mn::Vector2(1.0, 2.0)); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myVec3"), - Mn::Vector3(1.0, 2.0, 3.0)); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myVec4"), - Mn::Vector4(1.0, 2.0, 3.0, 4.0)); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myQuat"), - Mn::Quaternion({1.0, 2.0, 3.0}, 0.1)); - CORRADE_COMPARE(cfgToVerifyOverwrite->get("myRad"), Mn::Rad(1.23)); - - // Verify overwrite performed properly - compareSubconfigs(cfgToVerify, cfgToVerifyOverwrite); - } - -} // CoreTest::TestConfigurationSubconfigFind test - -} // namespace - -CORRADE_TEST_MAIN(CoreTest) diff --git a/src/tests/PhysicsTest.cpp b/src/tests/PhysicsTest.cpp index 81af04e28b..43d0bacc7d 100644 --- a/src/tests/PhysicsTest.cpp +++ b/src/tests/PhysicsTest.cpp @@ -224,7 +224,7 @@ void PhysicsTest::testJoinCompound() { objectTemplate->setJoinCollisionMeshes(true); } objectAttributesManager->registerObject(objectTemplate); - physicsManager_->reset(); + physicsManager_->reset(false); // add and simulate objects int num_objects = 7; @@ -302,7 +302,7 @@ void PhysicsTest::testCollisionBoundingBox() { objectTemplate->setBoundingBoxCollisions(true); } objectAttributesManager->registerObject(objectTemplate); - physicsManager_->reset(); + physicsManager_->reset(false); auto objectWrapper = makeObjectGetWrapper( objectFile, &sceneManager_->getSceneGraph(sceneID_).getDrawables()); @@ -612,7 +612,7 @@ void PhysicsTest::testMotionTypes() { // reset the scene rigidObjectManager_->removeAllObjects(); - physicsManager_->reset(); // time=0 + physicsManager_->reset(false); // time=0 } } } // PhysicsTest::testMotionTypes