diff --git a/data/test_assets/screenshots/ReplayBatchRendererTest_AO_batch.png b/data/test_assets/screenshots/ReplayBatchRendererTest_AO_batch.png new file mode 100644 index 0000000000..83239ef396 Binary files /dev/null and b/data/test_assets/screenshots/ReplayBatchRendererTest_AO_batch.png differ diff --git a/data/test_assets/urdf/fridge/fridge_scaled.urdf b/data/test_assets/urdf/fridge/fridge_scaled.urdf new file mode 100644 index 0000000000..67fade1014 --- /dev/null +++ b/data/test_assets/urdf/fridge/fridge_scaled.urdf @@ -0,0 +1,134 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/esp/gfx/replay/Recorder.cpp b/src/esp/gfx/replay/Recorder.cpp index 2095dd5037..f576ff28df 100644 --- a/src/esp/gfx/replay/Recorder.cpp +++ b/src/esp/gfx/replay/Recorder.cpp @@ -55,22 +55,7 @@ void Recorder::onCreateRenderAssetInstance( CORRADE_INTERNAL_ASSERT(findInstance(node) == ID_UNDEFINED); RenderAssetInstanceKey instanceKey = getNewInstanceKey(); - - auto adjustedCreation = creation; - - // We assume constant node scaling over the node's lifetime. Bake node scale - // into creation. - auto nodeScale = node->absoluteTransformation().scaling(); - // todo: check for reflection (rotationShear.determinant() < 0.0f) and bake - // into scaling (negate X scale). - if (nodeScale != Mn::Vector3(1.f, 1.f, 1.f)) { - adjustedCreation.scale = adjustedCreation.scale - ? *adjustedCreation.scale * nodeScale - : nodeScale; - } - - getKeyframe().creations.emplace_back(instanceKey, - std::move(adjustedCreation)); + getKeyframe().creations.emplace_back(instanceKey, creation); // Constructing NodeDeletionHelper here is equivalent to calling // node->addFeature. We keep a pointer to deletionHelper so we can delete it diff --git a/src/esp/physics/bullet/BulletPhysicsManager.cpp b/src/esp/physics/bullet/BulletPhysicsManager.cpp index 2074ef40a8..c4d55c238c 100644 --- a/src/esp/physics/bullet/BulletPhysicsManager.cpp +++ b/src/esp/physics/bullet/BulletPhysicsManager.cpp @@ -296,14 +296,14 @@ bool BulletPhysicsManager::attachLinkGeometry( Mn::Color4(material->m_matColor.m_specularColor); } + auto scale = Mn::Vector3{1.0f, 1.0f, 1.0f}; switch (visual.m_geometry.m_type) { case metadata::URDF::GEOM_CAPSULE: visualMeshInfo.type = esp::assets::AssetType::PRIMITIVE; // should be registered and cached already visualMeshInfo.filepath = visual.m_geometry.m_meshFileName; // scale by radius as suggested by magnum docs - visualGeomComponent.scale( - Mn::Vector3(visual.m_geometry.m_capsuleRadius)); + scale = Mn::Vector3(visual.m_geometry.m_capsuleRadius); // Magnum capsule is Y up, URDF is Z up visualGeomComponent.setTransformation( visualGeomComponent.transformation() * @@ -316,10 +316,9 @@ bool BulletPhysicsManager::attachLinkGeometry( visualMeshInfo.filepath = "cylinderSolid_rings_1_segments_12_halfLen_1_useTexCoords_false_" "useTangents_false_capEnds_true"; - visualGeomComponent.scale( - Mn::Vector3(visual.m_geometry.m_capsuleRadius, - visual.m_geometry.m_capsuleHeight / 2.0, - visual.m_geometry.m_capsuleRadius)); + scale = Mn::Vector3(visual.m_geometry.m_capsuleRadius, + visual.m_geometry.m_capsuleHeight / 2.0, + visual.m_geometry.m_capsuleRadius); // Magnum cylinder is Y up, URDF is Z up visualGeomComponent.setTransformation( visualGeomComponent.transformation() * @@ -328,17 +327,16 @@ bool BulletPhysicsManager::attachLinkGeometry( case metadata::URDF::GEOM_BOX: visualMeshInfo.type = esp::assets::AssetType::PRIMITIVE; visualMeshInfo.filepath = "cubeSolid"; - visualGeomComponent.scale(visual.m_geometry.m_boxSize * 0.5); + scale = visual.m_geometry.m_boxSize * 0.5; break; case metadata::URDF::GEOM_SPHERE: { visualMeshInfo.type = esp::assets::AssetType::PRIMITIVE; // default sphere prim is already constructed w/ radius 1 visualMeshInfo.filepath = "icosphereSolid_subdivs_1"; - visualGeomComponent.scale( - Mn::Vector3(visual.m_geometry.m_sphereRadius)); + scale = Mn::Vector3(visual.m_geometry.m_sphereRadius); } break; case metadata::URDF::GEOM_MESH: { - visualGeomComponent.scale(visual.m_geometry.m_meshScale); + scale = visual.m_geometry.m_meshScale; visualMeshInfo.filepath = visual.m_geometry.m_meshFileName; } break; case metadata::URDF::GEOM_PLANE: @@ -358,7 +356,7 @@ bool BulletPhysicsManager::attachLinkGeometry( flags |= assets::RenderAssetInstanceCreationInfo::Flag::IsRGBD; flags |= assets::RenderAssetInstanceCreationInfo::Flag::IsSemantic; assets::RenderAssetInstanceCreationInfo creation( - visualMeshInfo.filepath, Mn::Vector3{1}, flags, lightSetup); + visualMeshInfo.filepath, scale, flags, lightSetup); auto* geomNode = resourceManager_.loadAndCreateRenderAssetInstance( visualMeshInfo, creation, &visualGeomComponent, drawables, diff --git a/src/tests/BatchReplayRendererTest.cpp b/src/tests/BatchReplayRendererTest.cpp index 266ca0538d..0899d2b105 100644 --- a/src/tests/BatchReplayRendererTest.cpp +++ b/src/tests/BatchReplayRendererTest.cpp @@ -10,6 +10,7 @@ #include "esp/gfx/replay/Recorder.h" #include "esp/gfx/replay/ReplayManager.h" #include "esp/metadata/managers/ObjectAttributesManager.h" +#include "esp/physics/objectManagers/ArticulatedObjectManager.h" #include "esp/physics/objectManagers/RigidObjectManager.h" #include "esp/sensor/CameraSensor.h" #include "esp/sensor/Sensor.h" @@ -50,6 +51,7 @@ struct BatchReplayRendererTest : Cr::TestSuite::Tester { void testIntegration(); void testUnproject(); void testBatchPlayerDeletion(); + void testArticulatedObject(); void testClose(); const Magnum::Float maxThreshold = 255.f; @@ -157,6 +159,18 @@ const struct { }}, }; +const struct { + const char* name; + Cr::Containers::Pointer (*create)( + const ReplayRendererConfiguration& configuration); +} TestArticulatedObjectData[]{ + {"batch", + [](const ReplayRendererConfiguration& configuration) { + return Cr::Containers::Pointer{ + new esp::sim::BatchReplayRenderer{configuration}}; + }}, +}; + const struct { const char* name; Cr::Containers::Pointer (*create)( @@ -183,6 +197,11 @@ BatchReplayRendererTest::BatchReplayRendererTest() { addTests({&BatchReplayRendererTest::testBatchPlayerDeletion}); +#ifdef ESP_BUILD_WITH_BULLET + addInstancedTests({&BatchReplayRendererTest::testArticulatedObject}, + Cr::Containers::arraySize(TestArticulatedObjectData)); +#endif + addInstancedTests({&BatchReplayRendererTest::testClose}, Cr::Containers::arraySize(TestCloseData)); } // ctor @@ -470,6 +489,98 @@ void BatchReplayRendererTest::testBatchPlayerDeletion() { } } +void BatchReplayRendererTest::testArticulatedObject() { + auto&& data = TestArticulatedObjectData[testCaseInstanceId()]; + setTestCaseDescription(data.name); + + const auto sensorSpecs = getDefaultSensorSpecs(TestFlag::Color); + constexpr int numEnvs = 1; + const std::string userPrefix = "sensor_"; + const std::string screenshotPrefix = + "ReplayBatchRendererTest_AO_" + std::string(data.name); + + const std::string assetPath = + Cr::Utility::Path::join(TEST_ASSETS, "urdf/fridge/fridge.urdf"); + const std::string assetPathScaled = + Cr::Utility::Path::join(TEST_ASSETS, "urdf/fridge/fridge_scaled.urdf"); + std::vector serKeyframes; + + // Record sequence + { + SimulatorConfiguration simConfig{}; + simConfig.enableGfxReplaySave = true; + simConfig.createRenderer = false; + simConfig.enablePhysics = true; + auto sim = Simulator::create_unique(simConfig); + auto aoManager = sim->getArticulatedObjectManager(); + auto& sceneRoot = sim->getActiveSceneGraph().getRootNode(); + auto& recorder = *sim->getGfxReplayManager()->getRecorder(); + + { + auto fridgeA = aoManager->addArticulatedObjectFromURDF(assetPath); + CORRADE_COMPARE(aoManager->getNumObjects(), 1); + CORRADE_VERIFY(fridgeA); + fridgeA->setTranslation(Mn::Vector3(-5.0, -2.5, -2.5)); + + auto fridgeB = aoManager->addArticulatedObjectFromURDF(assetPathScaled); + CORRADE_COMPARE(aoManager->getNumObjects(), 2); + CORRADE_VERIFY(fridgeB); + fridgeB->setTranslation(Mn::Vector3(-5.0, -2.5, 2.5)); + + auto fridgeC = aoManager->addArticulatedObjectFromURDF( + assetPath, false, 0.5f /* Global scale */); + CORRADE_COMPARE(aoManager->getNumObjects(), 3); + CORRADE_VERIFY(fridgeC); + fridgeC->setTranslation(Mn::Vector3(-5.0, 2.5, -2.5)); + + auto fridgeD = aoManager->addArticulatedObjectFromURDF( + assetPathScaled, false, 0.5f /* Global scale */); + CORRADE_COMPARE(aoManager->getNumObjects(), 4); + CORRADE_VERIFY(fridgeD); + fridgeD->setTranslation(Mn::Vector3(-5.0, 2.5, 2.5)); + + auto& recorder = *sim->getGfxReplayManager()->getRecorder(); + for (const auto& sensor : sensorSpecs) { + recorder.addUserTransformToKeyframe( + userPrefix + sensor->uuid, Mn::Vector3(0.0f, 0.0f, 0.0f), + Mn::Quaternion::rotation(Mn::Deg(90.f), + Mn::Vector3(0.0f, 1.0f, 0.0f))); + } + + std::string serKeyframe = esp::gfx::replay::Recorder::keyframeToString( + recorder.extractKeyframe()); + serKeyframes.emplace_back(std::move(serKeyframe)); + } + } + CORRADE_COMPARE(serKeyframes.size(), 1); + + // Play sequence + { + ReplayRendererConfiguration batchRendererConfig; + batchRendererConfig.sensorSpecifications = sensorSpecs; + batchRendererConfig.numEnvironments = numEnvs; + batchRendererConfig.standalone = true; + Cr::Containers::Pointer renderer = + data.create(batchRendererConfig); + + std::vector colorBuffer; + std::vector colorImageView; + colorImageView.emplace_back(getRGBView( + renderer->sensorSize(0).x(), renderer->sensorSize(0).y(), colorBuffer)); + + renderer->setEnvironmentKeyframe(0, serKeyframes[0]); + renderer->setSensorTransformsFromKeyframe(0, userPrefix); + renderer->render(colorImageView, nullptr); + + // Test color output + std::string groundTruthImageFile = screenshotPrefix + ".png"; + CORRADE_COMPARE_WITH( + Mn::ImageView2D{colorImageView[0]}, + Cr::Utility::Path::join(screenshotDir, groundTruthImageFile), + (Mn::DebugTools::CompareImageToFile{maxThreshold, meanThreshold})); + } +} + void BatchReplayRendererTest::testClose() { auto&& data = TestIntegrationData[testCaseInstanceId()]; setTestCaseDescription(data.name); diff --git a/src/tests/MetadataMediatorTest.cpp b/src/tests/MetadataMediatorTest.cpp index 6f5d47c0fe..a67ce8c983 100644 --- a/src/tests/MetadataMediatorTest.cpp +++ b/src/tests/MetadataMediatorTest.cpp @@ -493,13 +493,13 @@ void MetadataMediatorTest::testDataset1() { ESP_WARNING() << "Starting test LoadArticulatedObjects"; const auto& aoAttributedsMgr = MM_->getAOAttributesManager(); int numAOHandles = aoAttributedsMgr->getNumObjects(); - // verify # of urdf filepaths loaded - should be 7; - CORRADE_COMPARE(numAOHandles, 7); + // verify # of urdf filepaths loaded - should be 8; + CORRADE_COMPARE(numAOHandles, 8); namespace Dir = Cr::Utility::Path; std::map urdfTestFilenames = aoAttributedsMgr->getArticulatedObjectModelFilenames(); - CORRADE_COMPARE(urdfTestFilenames.size(), 7); + CORRADE_COMPARE(urdfTestFilenames.size(), 8); // test that each stub name key corresponds to the actual file name passed // through the key making process for (std::map::const_iterator iter =