From 3bf35e8739db292fdc2199ce99c03d812c3f29ce Mon Sep 17 00:00:00 2001
From: John Turner <7strbass@gmail.com>
Date: Wed, 3 Jan 2024 13:58:24 -0500
Subject: [PATCH] --Convert AO scale to vector;

---
 docs/pages/attributesJSON.rst                 |  6 ++--
 src/esp/bindings/PhysicsObjectBindings.cpp    |  2 +-
 src/esp/metadata/URDFParser.cpp               | 13 ++++----
 src/esp/metadata/URDFParser.h                 | 31 +++++++++----------
 .../attributes/AbstractObjectAttributes.h     | 28 ++++++++++++-----
 .../ArticulatedObjectAttributes.cpp           | 10 +++---
 .../attributes/ArticulatedObjectAttributes.h  | 10 +++---
 .../metadata/managers/AOAttributesManager.cpp |  8 ++---
 src/esp/physics/ArticulatedObject.h           |  4 +--
 src/esp/physics/PhysicsManager.cpp            | 17 ++++++----
 src/esp/physics/PhysicsManager.h              |  6 ++--
 src/esp/physics/URDFImporter.cpp              |  2 +-
 .../physics/bullet/BulletPhysicsManager.cpp   |  5 ++-
 src/esp/physics/bullet/BulletURDFImporter.cpp |  1 +
 .../ArticulatedObjectManager.cpp              |  5 +--
 .../objectManagers/ArticulatedObjectManager.h | 12 ++++---
 .../objectWrappers/ManagedArticulatedObject.h |  4 +--
 src/tests/AttributesConfigsTest.cpp           |  4 +++
 src/tests/IOTest.cpp                          |  8 ++---
 19 files changed, 98 insertions(+), 78 deletions(-)

diff --git a/docs/pages/attributesJSON.rst b/docs/pages/attributesJSON.rst
index 1250a69f69..215f4559c3 100644
--- a/docs/pages/attributesJSON.rst
+++ b/docs/pages/attributesJSON.rst
@@ -370,9 +370,9 @@ Below are the handles and descriptors for the source URDF file and the render as
 Articulated Object Configuration And Rendering
 ----------------------------------------------
 
-"uniform_scale"
-    - double
-    - The uniform scaling to apply to this articulated object after load (defaults to 1.0). This is modifiable by the scene instance specification.
+"scale"
+    - 3-vector
+    - The scaling to apply to this articulated object after load (defaults to [1.0,1.0,1.0]). This is modifiable by the scene instance specification.
 "mass_scale"
     - double
     - The amount the mass of the articulated object should be scaled upon load (defaults to 1.0). This is modifiable by the scene instance specification.
diff --git a/src/esp/bindings/PhysicsObjectBindings.cpp b/src/esp/bindings/PhysicsObjectBindings.cpp
index eb046db50b..8adf64e226 100644
--- a/src/esp/bindings/PhysicsObjectBindings.cpp
+++ b/src/esp/bindings/PhysicsObjectBindings.cpp
@@ -443,7 +443,7 @@ void declareArticulatedObjectWrapper(py::module& m,
               .c_str())
       .def_property_readonly(
           "global_scale", &ManagedArticulatedObject::getGlobalScale,
-          R"(The uniform global scaling applied to this object during import.)")
+          R"(The global scaling vector applied to this object during import.)")
       .def("get_link_scene_node", &ManagedArticulatedObject::getLinkSceneNode,
            ("Get the scene node for this " + objType +
             "'s articulated link specified by the passed "
diff --git a/src/esp/metadata/URDFParser.cpp b/src/esp/metadata/URDFParser.cpp
index 46f17de59b..f30ebe0d5b 100644
--- a/src/esp/metadata/URDFParser.cpp
+++ b/src/esp/metadata/URDFParser.cpp
@@ -29,18 +29,17 @@ namespace esp {
 namespace metadata {
 namespace URDF {
 
-void Model::scaleShape(Shape& shape, float scale) {
+void Model::scaleShape(Shape& shape, const Mn::Vector3& scale) {
   shape.m_linkLocalFrame.translation() *= scale;
   switch (shape.m_geometry.m_type) {
+    case GEOM_SPHERE:
     case GEOM_MESH: {
       shape.m_geometry.m_meshScale *= scale;
     } break;
     case GEOM_BOX: {
       shape.m_geometry.m_boxSize *= scale;
     } break;
-    case GEOM_SPHERE: {
-      shape.m_geometry.m_sphereRadius *= double(scale);
-    } break;
+
     case GEOM_CAPSULE:
     case GEOM_CYLINDER: {
       shape.m_geometry.m_capsuleRadius *= double(scale);
@@ -51,14 +50,14 @@ void Model::scaleShape(Shape& shape, float scale) {
   }
 }
 
-void Model::setGlobalScaling(float scaling) {
+void Model::setGlobalScaling(const Mn::Vector3& scaling) {
   if (scaling == m_globalScaling) {
     // do nothing
     return;
   }
 
   // Need to re-scale model, so use the ratio of new to current scale
-  float scaleCorrection = scaling / m_globalScaling;
+  auto scaleCorrection = scaling / m_globalScaling;
 
   // scale all transforms' translations
   for (const auto& link : m_links) {
@@ -453,7 +452,7 @@ bool Parser::parseLink(const std::shared_ptr<Model>& model,
       ESP_VERY_VERBOSE() << link.m_name;
       return false;
     }
-    link.m_inertia.m_mass *= model->getGlobalScaling();
+    link.m_inertia.m_mass *= model->getGlobalScaling().product();
   } else {
     if ((strlen(linkName) == 5) && (strncmp(linkName, "world", 5)) == 0) {
       link.m_inertia.m_mass = 0.f;
diff --git a/src/esp/metadata/URDFParser.h b/src/esp/metadata/URDFParser.h
index c22284f8f2..13d3c9bd25 100644
--- a/src/esp/metadata/URDFParser.h
+++ b/src/esp/metadata/URDFParser.h
@@ -345,12 +345,12 @@ class Model {
    * @brief Set global scaling and re-scale an existing model. Modifies various
    * internal parameters.
    *
-   * @param scaling The new absolute uniform scale.
+   * @param scaling The new absolute scale.
    */
-  void setGlobalScaling(float scaling);
+  void setGlobalScaling(const Mn::Vector3& scaling);
 
   //! Get the currently configured global model scaling
-  float getGlobalScaling() const { return m_globalScaling; }
+  Mn::Vector3 getGlobalScaling() const { return m_globalScaling; }
 
   /**
    * @brief Set scaling for mass from initial values configured in URDF.
@@ -369,13 +369,13 @@ class Model {
   // scaling values which can be applied to the model after parsing
   //! Global euclidean scaling applied to the model's transforms, asset scales,
   //! and prismatic joint limits. Does not affect mass.
-  float m_globalScaling = 1.0;
+  Mn::Vector3 m_globalScaling = Mn::Vector3(1.0);
 
   //! Mass scaling of the model's Link inertias.
   float m_massScaling = 1.0;
 
   //! Scale the transformation and parameters of a Shape
-  void scaleShape(Shape& shape, float scale);
+  void scaleShape(Shape& shape, const Mn::Vector3& scale);
 };  // class model
 
 /**
@@ -383,9 +383,14 @@ class Model {
  * representation.
  */
 class Parser {
-  // URDF file path of last load call
-  std::string sourceFilePath_;
+ public:
+  Parser() = default;
 
+  // parse a loaded URDF string into relevant general data structures
+  // return false if the string is not a valid urdf or other error causes abort
+  bool parseURDF(const std::string& filename, std::shared_ptr<Model>& model);
+
+ private:
   /**
    * @brief Parse a transform into a Matrix4.
    *
@@ -522,16 +527,8 @@ class Parser {
    */
   bool validateMeshFile(std::string& filename);
 
- public:
-  Parser() = default;
-
-  // parse a loaded URDF string into relevant general data structures
-  // return false if the string is not a valid urdf or other error causes abort
-  bool parseURDF(const std::string& filename, std::shared_ptr<Model>& model);
-
-  // This is no longer used, instead set the urdf and physics subsystem to
-  // veryverbose, i.e. export HABITAT_SIM_LOG="urdf,physics=veryverbose" bool
-  // logMessages = false;
+  // URDF file path of last load call
+  std::string sourceFilePath_;
 };
 
 }  // namespace URDF
diff --git a/src/esp/metadata/attributes/AbstractObjectAttributes.h b/src/esp/metadata/attributes/AbstractObjectAttributes.h
index be9258bb38..f7392e3a2a 100644
--- a/src/esp/metadata/attributes/AbstractObjectAttributes.h
+++ b/src/esp/metadata/attributes/AbstractObjectAttributes.h
@@ -26,22 +26,34 @@ class AbstractObjectAttributes : public AbstractAttributes {
   ~AbstractObjectAttributes() override = default;
 
   /**
-   * @brief Scale of the ojbect
+   * @brief Set the scale of the object
    */
   void setScale(const Magnum::Vector3& scale) { set("scale", scale); }
+  /**
+   * @brief Get the scale of the object
+   */
   Magnum::Vector3 getScale() const { return get<Magnum::Vector3>("scale"); }
 
   /**
-   * @brief collision shape inflation margin
+   * @brief Set the collision shape inflation margin
    */
   void setMargin(double margin) { set("margin", margin); }
+  /**
+   * @brief Get the collision shape inflation margin
+   */
   double getMargin() const { return get<double>("margin"); }
 
-  // if object should be checked for collisions - if other objects can collide
-  // with this object
+  /**
+   * @brief Set if object should be checked for collisions - if other objects
+   * can collide with this object
+   */
   void setIsCollidable(bool isCollidable) {
     set("is_collidable", isCollidable);
   }
+  /**
+   * @brief Get if object should be checked for collisions - if other objects
+   * can collide with this object
+   */
   bool getIsCollidable() const { return get<bool>("is_collidable"); }
 
   /**
@@ -49,7 +61,7 @@ class AbstractObjectAttributes : public AbstractAttributes {
    */
   void setOrientUp(const Magnum::Vector3& orientUp) { set("up", orientUp); }
   /**
-   * @brief get default up orientation for object/stage mesh
+   * @brief Get default up orientation for object/stage mesh
    */
   Magnum::Vector3 getOrientUp() const { return get<Magnum::Vector3>("up"); }
   /**
@@ -59,7 +71,7 @@ class AbstractObjectAttributes : public AbstractAttributes {
     set("front", orientFront);
   }
   /**
-   * @brief get default forward orientation for object/stage mesh
+   * @brief Get default forward orientation for object/stage mesh
    */
   Magnum::Vector3 getOrientFront() const {
     return get<Magnum::Vector3>("front");
@@ -576,7 +588,7 @@ class AbstractObjectAttributes : public AbstractAttributes {
 
   std::string getObjectInfoHeaderInternal() const override;
   /**
-   * @brief get AbstractObject specific info header
+   * @brief Get AbstractObject specific info header
    */
   virtual std::string getAbstractObjectInfoHeaderInternal() const {
     return "";
@@ -588,7 +600,7 @@ class AbstractObjectAttributes : public AbstractAttributes {
    */
   std::string getObjectInfoInternal() const override;
   /**
-   * @brief get AbstractObject specific info for csv string
+   * @brief Get AbstractObject specific info for csv string
    */
   virtual std::string getAbstractObjectInfoInternal() const { return ""; };
 
diff --git a/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp b/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp
index ba19c0b70c..d7c20c6af8 100644
--- a/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp
+++ b/src/esp/metadata/attributes/ArticulatedObjectAttributes.cpp
@@ -36,7 +36,7 @@ ArticulatedObjectAttributes::ArticulatedObjectAttributes(
   initTranslated("shader_type",
                  getShaderTypeName(ObjectInstanceShaderType::Material));
 
-  init("uniform_scale", 1.0f);
+  init("scale", Mn::Vector3{1.0, 1.0, 1.0});
   init("mass_scale", 1.0);
 
   // Initialize these so they exist in the configuration
@@ -56,8 +56,8 @@ void ArticulatedObjectAttributes::writeValuesToJson(
   writeValueToJson("urdf_filepath", jsonObj, allocator);
   writeValueToJson("render_asset", jsonObj, allocator);
   writeValueToJson("semantic_id", jsonObj, allocator);
-  if (getUniformScale() != 1.0f) {
-    writeValueToJson("uniform_scale", jsonObj, allocator);
+  if (getScale() != Mn::Vector3(1.0, 1.0, 1.0)) {
+    writeValueToJson("scale", jsonObj, allocator);
   }
   if (getMassScale() != 1.0) {
     writeValueToJson("mass_scale", jsonObj, allocator);
@@ -70,14 +70,14 @@ void ArticulatedObjectAttributes::writeValuesToJson(
 }  // ArticulatedObjectAttributes::writeValuesToJson
 
 std::string ArticulatedObjectAttributes::getObjectInfoHeaderInternal() const {
-  return "URDF Filepath,Render Asset,Semantic ID,Uniform Scale,Mass Scale,Base "
+  return "URDF Filepath,Render Asset,Semantic ID,Scale,Mass Scale,Base "
          "Type,Inertia Source,Link Order,Render Mode,Current Shader Type,";
 }  // ArticulatedObjectAttributes::getObjectInfoHeaderInternal
 
 std::string ArticulatedObjectAttributes::getObjectInfoInternal() const {
   return Cr::Utility::formatString(
       "{},{},{},{},{},{},{},{},{},{}", getURDFPath(), getRenderAssetHandle(),
-      getAsString("semantic_id"), getAsString("uniform_scale"),
+      getAsString("semantic_id"), getAsString("scale"),
       getAsString("mass_scale"), getAOBaseTypeName(getBaseType()),
       getAOInertiaSourceName(getInertiaSource()),
       getAOLinkOrderName(getLinkOrder()), getAORenderModeName(getRenderMode()),
diff --git a/src/esp/metadata/attributes/ArticulatedObjectAttributes.h b/src/esp/metadata/attributes/ArticulatedObjectAttributes.h
index 87998b450d..ed544dce3f 100644
--- a/src/esp/metadata/attributes/ArticulatedObjectAttributes.h
+++ b/src/esp/metadata/attributes/ArticulatedObjectAttributes.h
@@ -82,15 +82,13 @@ class ArticulatedObjectAttributes : public AbstractAttributes {
   }
 
   /**
-   * @brief Set uniform scaling of the articulated object.
+   * @brief Set scaling vector of the articulated object.
    */
-  void setUniformScale(float scale) { set("uniform_scale", scale); }
+  void setScale(const Magnum::Vector3& scale) { set("scale", scale); }
   /**
-   * @brief Get uniform scaling of the articulated object.
+   * @brief Get the scale vector of the articulated object.
    */
-  float getUniformScale() const {
-    return static_cast<float>(get<double>("uniform_scale"));
-  }
+  Magnum::Vector3 getScale() const { return get<Magnum::Vector3>("scale"); }
 
   /**
    * @brief Set mass scaling of the articulated object.
diff --git a/src/esp/metadata/managers/AOAttributesManager.cpp b/src/esp/metadata/managers/AOAttributesManager.cpp
index 5b047ef636..0f003c1b03 100644
--- a/src/esp/metadata/managers/AOAttributesManager.cpp
+++ b/src/esp/metadata/managers/AOAttributesManager.cpp
@@ -61,10 +61,10 @@ void AOAttributesManager::setValsFromJSONDoc(
     aoAttr->setSemanticId(semantic_id);
   });
 
-  // load the uniform scaling
-  io::jsonIntoSetter<double>(
-      jsonConfig, "uniform_scale",
-      [aoAttr](double scale) { aoAttr->setUniformScale(scale); });
+  // scale
+  io::jsonIntoConstSetter<Magnum::Vector3>(
+      jsonConfig, "scale",
+      [aoAttr](const Magnum::Vector3& scale) { aoAttr->setScale(scale); });
 
   // load the mass scaling
   io::jsonIntoSetter<double>(jsonConfig, "mass_scale", [aoAttr](double scale) {
diff --git a/src/esp/physics/ArticulatedObject.h b/src/esp/physics/ArticulatedObject.h
index 54f73bc600..00051ee718 100644
--- a/src/esp/physics/ArticulatedObject.h
+++ b/src/esp/physics/ArticulatedObject.h
@@ -322,7 +322,7 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase {
    * @brief Get the uniform global scaling applied to this object during import.
    * @return The global scaling applied to the object.
    */
-  float getGlobalScale() const { return globalScale_; }
+  Mn::Vector3 getGlobalScale() const { return globalScale_; }
 
   /**
    * @brief Get a const reference to an ArticulatedLink SceneNode for
@@ -1108,7 +1108,7 @@ class ArticulatedObject : public esp::physics::PhysicsObjectBase {
   bool autoClampJointLimits_ = false;
 
   //! Cache the global scaling from the source model. Set during import.
-  float globalScale_ = 1.0;
+  Mn::Vector3 globalScale_ = Mn::Vector3(1.0);
 
   //! Cache the cumulative bounding box of the AO heirarchy in root local space.
   //! This is necessary because the child links are not children of the root
diff --git a/src/esp/physics/PhysicsManager.cpp b/src/esp/physics/PhysicsManager.cpp
index 35875e2dd5..7b76e61be9 100644
--- a/src/esp/physics/PhysicsManager.cpp
+++ b/src/esp/physics/PhysicsManager.cpp
@@ -429,7 +429,7 @@ int PhysicsManager::addArticulatedObjectFromURDF(
     const std::string& filepath,
     DrawableGroup* drawables,
     bool fixedBase,
-    float globalScale,
+    const Mn::Vector3& globalScale,
     float massScale,
     bool forceReload,
     bool maintainLinkOrder,
@@ -450,7 +450,7 @@ int PhysicsManager::addArticulatedObjectFromURDF(
                                                                     true);
 
   // Set pertinent values
-  artObjAttributes->setUniformScale(globalScale);
+  artObjAttributes->setScale(globalScale);
   artObjAttributes->setMassScale(static_cast<double>(massScale));
 
   artObjAttributes->setBaseType(metadata::attributes::getAOBaseTypeName(
@@ -529,16 +529,21 @@ int PhysicsManager::addArticulatedObjectInstance(
     artObjAttributes->setShaderType(getShaderTypeName(artObjShaderType));
   }
 
-  // set uniform scale
-  artObjAttributes->setUniformScale(artObjAttributes->getUniformScale() *
-                                    aObjInstAttributes->getUniformScale());
+  // set scaling values for this instance of articulated object attributes -
+  // first uniform scaling
+  artObjAttributes->setScale(artObjAttributes->getScale() *
+                             aObjInstAttributes->getUniformScale());
+  // set scaling values for this instance of object attributes - next
+  // non-uniform scaling
+  artObjAttributes->setScale(artObjAttributes->getScale() *
+                             aObjInstAttributes->getNonUniformScale());
 
   // If boolean specifies to do so, apply geometric scaling to mass (product of
   // scale values)
   if (aObjInstAttributes->getApplyScaleToMass()) {
     artObjAttributes->setMassScale(
         artObjAttributes->getMassScale() *
-        static_cast<double>(artObjAttributes->getUniformScale()));
+        static_cast<double>(artObjAttributes->getScale().product()));
   }
 
   // set scaled mass
diff --git a/src/esp/physics/PhysicsManager.h b/src/esp/physics/PhysicsManager.h
index 65ffbb62d2..2c934c0cf2 100644
--- a/src/esp/physics/PhysicsManager.h
+++ b/src/esp/physics/PhysicsManager.h
@@ -520,8 +520,8 @@ class PhysicsManager : public std::enable_shared_from_this<PhysicsManager> {
    * query Simulator to retrieve a group.
    * @param fixedBase Whether the base of the @ref ArticulatedObject should be
    * fixed.
-   * @param globalScale A scale multiplier to be applied uniformly in 3
-   * dimensions to the entire @ref ArticulatedObject.
+   * @param globalScale A scale multiplier to be applied in 3 dimensions to the
+   * entire @ref ArticulatedObject.
    * @param massScale A scale multiplier to be applied to the mass of the all
    * the components of the @ref ArticulatedObject.
    * @param forceReload If true, reload the source URDF from file, replacing the
@@ -541,7 +541,7 @@ class PhysicsManager : public std::enable_shared_from_this<PhysicsManager> {
       const std::string& filepath,
       DrawableGroup* drawables = nullptr,
       bool fixedBase = false,
-      float globalScale = 1.0,
+      const Mn::Vector3& globalScale = {1.0, 1.0, 1.0},
       float massScale = 1.0,
       bool forceReload = false,
       bool maintainLinkOrder = false,
diff --git a/src/esp/physics/URDFImporter.cpp b/src/esp/physics/URDFImporter.cpp
index 7d12cdbe8c..77800cdf2c 100644
--- a/src/esp/physics/URDFImporter.cpp
+++ b/src/esp/physics/URDFImporter.cpp
@@ -249,7 +249,7 @@ void URDFImporter::importURDFAssets(
     return;
   }
   // re-scale the cached model
-  activeModel_->setGlobalScaling(artObjAttributes->getUniformScale());
+  activeModel_->setGlobalScaling(artObjAttributes->getScale());
   activeModel_->setMassScaling(artObjAttributes->getMassScale());
 
   for (size_t linkIx = 0; linkIx < activeModel_->m_links.size(); ++linkIx) {
diff --git a/src/esp/physics/bullet/BulletPhysicsManager.cpp b/src/esp/physics/bullet/BulletPhysicsManager.cpp
index ce09ed0b3d..ef1deecf12 100644
--- a/src/esp/physics/bullet/BulletPhysicsManager.cpp
+++ b/src/esp/physics/bullet/BulletPhysicsManager.cpp
@@ -330,7 +330,7 @@ bool BulletPhysicsManager::attachLinkGeometry(
         visualMeshInfo.type = AssetType::Primitive;
         // default sphere prim is already constructed w/ radius 1
         visualMeshInfo.filepath = "icosphereSolid_subdivs_1";
-        scale = Mn::Vector3(visual.m_geometry.m_sphereRadius);
+        scale = visual.m_geometry.m_meshScale;
       } break;
       case metadata::URDF::GEOM_MESH: {
         scale = visual.m_geometry.m_meshScale;
@@ -944,8 +944,7 @@ void BulletPhysicsManager::instantiateSkinnedModel(
   assets::RenderAssetInstanceCreationInfo creationInfo;
   creationInfo.filepath = renderAssetPath;
   creationInfo.lightSetupKey = lightSetupKey;
-  creationInfo.scale =
-      artObjAttributes->getUniformScale() * Mn::Vector3(1.f, 1.f, 1.f);
+  creationInfo.scale = artObjAttributes->getScale();
   esp::assets::RenderAssetInstanceCreationInfo::Flags flags;
   flags |= esp::assets::RenderAssetInstanceCreationInfo::Flag::IsRGBD;
   flags |= esp::assets::RenderAssetInstanceCreationInfo::Flag::IsSemantic;
diff --git a/src/esp/physics/bullet/BulletURDFImporter.cpp b/src/esp/physics/bullet/BulletURDFImporter.cpp
index 8b584b41e9..538b095e1b 100644
--- a/src/esp/physics/bullet/BulletURDFImporter.cpp
+++ b/src/esp/physics/bullet/BulletURDFImporter.cpp
@@ -86,6 +86,7 @@ btCollisionShape* BulletURDFImporter::convertURDFToCollisionShape(
       float radius = collision->m_geometry.m_sphereRadius;
       auto sphereShape = std::make_unique<btSphereShape>(radius);
       shape = sphereShape.get();
+      shape->setLocalScaling(btVector3(collision->m_geometry.m_meshScale));
       shape->setMargin(gUrdfDefaultCollisionMargin);
       linkChildShapes.emplace_back(std::move(sphereShape));
       break;
diff --git a/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp b/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp
index 959d596eab..2ec8092594 100644
--- a/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp
+++ b/src/esp/physics/objectManagers/ArticulatedObjectManager.cpp
@@ -42,8 +42,9 @@ ArticulatedObjectManager::addArticulatedObjectFromURDF(
     const std::string& lightSetup) {
   if (auto physMgr = this->getPhysicsManager()) {
     int newAObjID = physMgr->addArticulatedObjectFromURDF(
-        filepath, nullptr, fixedBase, globalScale, massScale, forceReload,
-        maintainLinkOrder, intertiaFromURDF, lightSetup);
+        filepath, nullptr, fixedBase, {globalScale, globalScale, globalScale},
+        massScale, forceReload, maintainLinkOrder, intertiaFromURDF,
+        lightSetup);
     return this->getObjectCopyByID(newAObjID);
   }
   return nullptr;
diff --git a/src/esp/physics/objectManagers/ArticulatedObjectManager.h b/src/esp/physics/objectManagers/ArticulatedObjectManager.h
index fbca227396..2d66f4dc65 100644
--- a/src/esp/physics/objectManagers/ArticulatedObjectManager.h
+++ b/src/esp/physics/objectManagers/ArticulatedObjectManager.h
@@ -24,8 +24,10 @@ class ArticulatedObjectManager
 
   /**
    * @brief Load, parse, and import a URDF file instantiating an @ref
-   * BulletArticulatedObject in the world.  This version does not require
-   * drawables to be specified.
+   * BulletArticulatedObject in the world. The values passed as arguments will
+   * override the specified values in any existing @ref ArticulatedObjectAttributes
+   * describing this URDF's construction.
+   *
    * @param filepath The fully-qualified filename for the URDF file describing
    * the model the articulated object is to be built from.
    * @param fixedBase Whether the base of the @ref ArticulatedObject should be
@@ -56,8 +58,10 @@ class ArticulatedObjectManager
 
   /**
    * @brief Cast to BulletArticulatedObject version.  Load, parse, and import a
-   * URDF file instantiating an @ref BulletArticulatedObject in the world.  This
-   * version does not require drawables to be specified.
+   * URDF file instantiating an @ref BulletArticulatedObject in the world. The
+   * values passed as arguments will override the specified values in any
+   * existing @ref ArticulatedObjectAttributes describing this URDF's construction.
+   *
    * @param filepath The fully-qualified filename for the URDF file describing
    * the model the articulated object is to be built from.
    * @param fixedBase Whether the base of the @ref ArticulatedObject should be
diff --git a/src/esp/physics/objectWrappers/ManagedArticulatedObject.h b/src/esp/physics/objectWrappers/ManagedArticulatedObject.h
index 608f577df1..b82766d2f4 100644
--- a/src/esp/physics/objectWrappers/ManagedArticulatedObject.h
+++ b/src/esp/physics/objectWrappers/ManagedArticulatedObject.h
@@ -41,11 +41,11 @@ class ManagedArticulatedObject
     return nullptr;
   }  // getInitializationAttributes()
 
-  float getGlobalScale() const {
+  Mn::Vector3 getGlobalScale() const {
     if (auto sp = getObjectReference()) {
       return sp->getGlobalScale();
     }
-    return 1.0;
+    return Mn::Vector3(1.0);
   }
 
   scene::SceneNode* getLinkSceneNode(int linkId = BASELINK_ID) const {
diff --git a/src/tests/AttributesConfigsTest.cpp b/src/tests/AttributesConfigsTest.cpp
index 97d8bb04f4..aa4baf5122 100644
--- a/src/tests/AttributesConfigsTest.cpp
+++ b/src/tests/AttributesConfigsTest.cpp
@@ -1869,6 +1869,8 @@ void AttributesConfigsTest::testArticulatedObjectAttrVals(
     const std::string& assetPath,
     const std::string& urdfPath) {
   // match values set in test JSON
+  CORRADE_COMPARE(artObjAttr->getScale(), Mn::Vector3(4, 3, 2));
+  CORRADE_COMPARE(artObjAttr->getMassScale(), 2.1);
   CORRADE_COMPARE(artObjAttr->getURDFFullPath(), urdfPath);
   CORRADE_COMPARE(artObjAttr->getRenderAssetFullPath(), assetPath);
   CORRADE_COMPARE(artObjAttr->getSemanticId(), 100);
@@ -2014,6 +2016,8 @@ void AttributesConfigsTest::testArticulatedObjectAttrVals(
 void AttributesConfigsTest::testArticulatedObjectJSONLoad() {
   // build JSON sample config
   const std::string& jsonString = R"({
+  "scale":[4,3,2],
+  "mass_scale":2.1,
   "urdf_filepath": "urdf_test_file.urdf",
   "render_asset": "testAO_JSONRenderAsset.glb",
   "semantic_id": 100,
diff --git a/src/tests/IOTest.cpp b/src/tests/IOTest.cpp
index 100ee1ee3c..7121899127 100644
--- a/src/tests/IOTest.cpp
+++ b/src/tests/IOTest.cpp
@@ -215,15 +215,15 @@ void IOTest::parseURDF() {
   CORRADE_COMPARE(urdfModel->m_materials.size(), 3);
 
   // check global scaling
-  CORRADE_COMPARE(urdfModel->getGlobalScaling(), 1.0);
+  CORRADE_COMPARE(urdfModel->getGlobalScaling(), Mn::Vector3{1.0});
   // this link is a mesh shape, so check the mesh scale
   CORRADE_COMPARE(
       urdfModel->getLink(1)->m_collisionArray.back().m_geometry.m_type, 5);
   CORRADE_COMPARE(
       urdfModel->getLink(1)->m_collisionArray.back().m_geometry.m_meshScale,
       Mn::Vector3{1.0});
-  urdfModel->setGlobalScaling(2.0);
-  CORRADE_COMPARE(urdfModel->getGlobalScaling(), 2.0);
+  urdfModel->setGlobalScaling(Mn::Vector3{2.0});
+  CORRADE_COMPARE(urdfModel->getGlobalScaling(), Mn::Vector3{2.0});
   CORRADE_COMPARE(
       urdfModel->getLink(1)->m_collisionArray.back().m_geometry.m_meshScale,
       Mn::Vector3{2.0});
@@ -238,7 +238,7 @@ void IOTest::parseURDF() {
   // test overwrite re-load
   parser.parseURDF(attributes->getURDFPath(), urdfModel);
   // should have default values again
-  CORRADE_COMPARE(urdfModel->getGlobalScaling(), 1.0);
+  CORRADE_COMPARE(urdfModel->getGlobalScaling(), Mn::Vector3{1.0});
   CORRADE_COMPARE(urdfModel->getMassScaling(), 1.0);
   CORRADE_COMPARE(
       urdfModel->getLink(1)->m_collisionArray.back().m_geometry.m_meshScale,