diff --git a/src/esp/geo/CoordinateFrame.h b/src/esp/geo/CoordinateFrame.h index dee3b3a8c7..ca1c12a167 100644 --- a/src/esp/geo/CoordinateFrame.h +++ b/src/esp/geo/CoordinateFrame.h @@ -11,49 +11,47 @@ namespace esp { namespace geo { -namespace Mn = Magnum; - //! Represents a frame of reference defined by an origin and //! two semantically meaningful directions: "up" and "front", or //! equivalently "gravity" and "back" class CoordinateFrame { public: - explicit CoordinateFrame(const Mn::Vector3& up = ESP_UP, - const Mn::Vector3& front = ESP_FRONT, - const Mn::Vector3& origin = {}); - explicit CoordinateFrame(const Mn::Quaternion& rotation, - const Mn::Vector3& origin = {}); + explicit CoordinateFrame(const Magnum::Vector3& up = ESP_UP, + const Magnum::Vector3& front = ESP_FRONT, + const Magnum::Vector3& origin = {}); + explicit CoordinateFrame(const Magnum::Quaternion& rotation, + const Magnum::Vector3& origin = {}); //! Returns position of origin of this CoordinateFrame relative to parent - Mn::Vector3 origin() const { return origin_; } + Magnum::Vector3 origin() const { return origin_; } //! Returns up orientation - Mn::Vector3 up() const { return up_; } + Magnum::Vector3 up() const { return up_; } //! Returns down/gravity orientation - Mn::Vector3 gravity() const { return -up_; } + Magnum::Vector3 gravity() const { return -up_; } //! Returns front orientation - Mn::Vector3 front() const { return front_; } + Magnum::Vector3 front() const { return front_; } //! Returns front orientation - Mn::Vector3 back() const { return -front_; } + Magnum::Vector3 back() const { return -front_; } //! Returns quaternion representing the rotation taking direction vectors in //! world coordinates to direction vectors in this CoordinateFrame - Mn::Quaternion rotationWorldToFrame() const; + Magnum::Quaternion rotationWorldToFrame() const; //! Returns quaternion representing the rotation taking direction vectors in //! this CoordinateFrame to direction vectors in world coordinates - Mn::Quaternion rotationFrameToWorld() const; + Magnum::Quaternion rotationFrameToWorld() const; //! Returns a stringified JSON representation of this CoordinateFrame std::string toString() const; protected: - Mn::Vector3 up_; - Mn::Vector3 front_; - Mn::Vector3 origin_; + Magnum::Vector3 up_; + Magnum::Vector3 front_; + Magnum::Vector3 origin_; ESP_SMART_POINTERS(CoordinateFrame) }; diff --git a/src/esp/nav/PathFinder.cpp b/src/esp/nav/PathFinder.cpp index 420631e589..2354a0a11d 100644 --- a/src/esp/nav/PathFinder.cpp +++ b/src/esp/nav/PathFinder.cpp @@ -1372,7 +1372,8 @@ Mn::Vector3 PathFinder::Impl::getRandomNavigablePointAroundSphere( status = navQuery_->findRandomPointAroundCircle( start_ref, circleCenter.data(), radius, filter_.get(), frand, &rand_ref, pt.data()); - if (dtStatusSucceed(status) && (pt - circleCenter).length() <= radius) { + if (dtStatusSucceed(status) && + (pt - circleCenter).dot() <= radius * radius) { break; } } diff --git a/src/esp/scene/ObjectControls.cpp b/src/esp/scene/ObjectControls.cpp index e8138f529b..6108fd4628 100644 --- a/src/esp/scene/ObjectControls.cpp +++ b/src/esp/scene/ObjectControls.cpp @@ -97,8 +97,7 @@ ObjectControls& ObjectControls::action(SceneNode& object, const auto endPos = object.absoluteTransformation().translation(); const Mn::Vector3 filteredEndPosition = moveFilterFunc_(startPosition, endPos); - object.translate( - Magnum::Vector3(Mn::Vector3(filteredEndPosition - endPos))); + object.translate(filteredEndPosition - endPos); } else { moveFuncMapIter->second(object, distance); } diff --git a/src/esp/scene/ObjectControls.h b/src/esp/scene/ObjectControls.h index 7214fe4b0b..540376b02a 100644 --- a/src/esp/scene/ObjectControls.h +++ b/src/esp/scene/ObjectControls.h @@ -44,9 +44,10 @@ class ObjectControls { } protected: - MoveFilterFunc moveFilterFunc_ = - [](CORRADE_UNUSED const Magnum::Vector3& start, - const Magnum::Vector3& end) { return end; }; + MoveFilterFunc moveFilterFunc_ = [](const Magnum::Vector3& /*start*/, + const Magnum::Vector3& end) { + return end; + }; std::map moveFuncMap_; ESP_SMART_POINTERS(ObjectControls) diff --git a/src/esp/scene/ReplicaSemanticScene.cpp b/src/esp/scene/ReplicaSemanticScene.cpp index 69c45c89f9..d2358371a7 100644 --- a/src/esp/scene/ReplicaSemanticScene.cpp +++ b/src/esp/scene/ReplicaSemanticScene.cpp @@ -17,11 +17,9 @@ namespace scene { constexpr int kMaxIds = 10000; /* We shouldn't every need more than this. */ -bool SemanticScene::loadReplicaHouse( - const std::string& houseFilename, - SemanticScene& scene, - const Magnum::Quaternion& - worldRotation /* = Magnum::Quaternion::Identity() */) { +bool SemanticScene::loadReplicaHouse(const std::string& houseFilename, + SemanticScene& scene, + const Magnum::Quaternion& worldRotation) { if (!checkFileExists(houseFilename, "loadReplicaHouse")) { return false; } diff --git a/src/esp/sensor/CameraSensor.cpp b/src/esp/sensor/CameraSensor.cpp index 61d759c98f..5934f12038 100644 --- a/src/esp/sensor/CameraSensor.cpp +++ b/src/esp/sensor/CameraSensor.cpp @@ -44,8 +44,8 @@ namespace { hFoV from the CameraSensorSpec */ Mn::Matrix4 projectionMatrixInternal(const CameraSensorSpec& spec, Mn::Rad hfov) { - const Mn::Vector2 nearPlaneSize{ - 1.0f, Mn::Vector2{Mn::Vector2i{spec.resolution}}.aspectRatio()}; + const Mn::Vector2 nearPlaneSize{1.0f, + Mn::Vector2{spec.resolution}.aspectRatio()}; if (spec.sensorSubType == SensorSubType::Orthographic) { return Mn::Matrix4::orthographicProjection(nearPlaneSize / spec.orthoScale, spec.near, spec.far); diff --git a/src/esp/sensor/FisheyeSensor.cpp b/src/esp/sensor/FisheyeSensor.cpp index 7883dbb6db..450d1ec63f 100644 --- a/src/esp/sensor/FisheyeSensor.cpp +++ b/src/esp/sensor/FisheyeSensor.cpp @@ -52,7 +52,7 @@ Magnum::Vector2 computePrincipalPointOffset(const FisheyeSensorSpec& spec) { if (bool(spec.principalPointOffset)) { return *spec.principalPointOffset; } - return Mn::Vector2(spec.resolution[0], spec.resolution[1]) * 0.5f; + return Mn::Vector2{spec.resolution} * 0.5f; } FisheyeSensor::FisheyeSensor(scene::SceneNode& cameraNode, diff --git a/src/tests/GeoTest.cpp b/src/tests/GeoTest.cpp index e698a3a4db..f994bc6f2a 100644 --- a/src/tests/GeoTest.cpp +++ b/src/tests/GeoTest.cpp @@ -131,15 +131,15 @@ void GeoTest::obbConstruction() { core::quatRotFromTwoVectors(Mn::Vector3::yAxis(), Mn::Vector3::zAxis()); OBB obb2(center, dimensions, rot1); - CORRADE_VERIFY(obb2.center() == center); - CORRADE_VERIFY(obb2.sizes() == dimensions); - CORRADE_VERIFY(obb2.halfExtents() == dimensions / 2); - CORRADE_VERIFY(obb2.rotation() == rot1); + CORRADE_COMPARE(obb2.center(), center); + CORRADE_COMPARE(obb2.sizes(), dimensions); + CORRADE_COMPARE(obb2.halfExtents(), dimensions / 2); + CORRADE_COMPARE(obb2.rotation(), rot1); Mn::Range3D aabb(Mn::Vector3(-1, -2, -3), Mn::Vector3(3, 2, 1)); OBB obb3(aabb); - CORRADE_VERIFY(obb3.center() == aabb.center()); - CORRADE_VERIFY(obb3.toAABB() == aabb); + CORRADE_COMPARE(obb3.center(), aabb.center()); + CORRADE_COMPARE(obb3.toAABB(), aabb); } void GeoTest::obbFunctions() { @@ -160,7 +160,7 @@ void GeoTest::obbFunctions() { CORRADE_COMPARE(aabb.max(), (Mn::Vector3{10.0f, 5.0f, 1.0f})); const auto identity = obb2.worldToLocal() * obb2.localToWorld(); - CORRADE_VERIFY(identity == Mn::Matrix4()); + CORRADE_COMPARE(identity, Mn::Matrix4()); CORRADE_VERIFY( obb2.contains(obb2.localToWorld().transformPoint(Mn::Vector3(0, 0, 0)))); CORRADE_VERIFY( @@ -182,25 +182,25 @@ void GeoTest::coordinateFrame() { Mn::Matrix4 xform = Mn::Matrix4::from(rotation.toMatrix(), origin); CoordinateFrame c1(up, front, origin); - CORRADE_VERIFY(c1.up() == up); - CORRADE_VERIFY(c1.gravity() == -up); - CORRADE_VERIFY(c1.front() == front); - CORRADE_VERIFY(c1.back() == -front); - CORRADE_VERIFY(c1.up() == rotation.transformVectorNormalized(ESP_UP)); - CORRADE_VERIFY(c1.front() == rotation.transformVectorNormalized(ESP_FRONT)); - CORRADE_VERIFY(c1.origin() == origin); - CORRADE_VERIFY(c1.rotationWorldToFrame() == rotation); + CORRADE_COMPARE(c1.up(), up); + CORRADE_COMPARE(c1.gravity(), -up); + CORRADE_COMPARE(c1.front(), front); + CORRADE_COMPARE(c1.back(), -front); + CORRADE_COMPARE(c1.up(), rotation.transformVectorNormalized(ESP_UP)); + CORRADE_COMPARE(c1.front(), rotation.transformVectorNormalized(ESP_FRONT)); + CORRADE_COMPARE(c1.origin(), origin); + CORRADE_COMPARE(c1.rotationWorldToFrame(), rotation); CoordinateFrame c2(rotation, origin); - CORRADE_VERIFY(c1 == c2); - CORRADE_VERIFY(c2.up() == up); - CORRADE_VERIFY(c2.gravity() == -up); - CORRADE_VERIFY(c2.front() == front); - CORRADE_VERIFY(c2.back() == -front); - CORRADE_VERIFY(c2.up() == rotation.transformVectorNormalized(ESP_UP)); - CORRADE_VERIFY(c2.front() == rotation.transformVectorNormalized(ESP_FRONT)); - CORRADE_VERIFY(c2.origin() == origin); - CORRADE_VERIFY(c2.rotationWorldToFrame() == rotation); + CORRADE_COMPARE(c1, c2); + CORRADE_COMPARE(c2.up(), up); + CORRADE_COMPARE(c2.gravity(), -up); + CORRADE_COMPARE(c2.front(), front); + CORRADE_COMPARE(c2.back(), -front); + CORRADE_COMPARE(c2.up(), rotation.transformVectorNormalized(ESP_UP)); + CORRADE_COMPARE(c2.front(), rotation.transformVectorNormalized(ESP_FRONT)); + CORRADE_COMPARE(c2.origin(), origin); + CORRADE_COMPARE(c2.rotationWorldToFrame(), rotation); const std::string j = R"({"up":[0,0,1],"front":[-1,0,0],"origin":[1,-2,3]})"; CORRADE_COMPARE(c1.toString(), j); diff --git a/src/tests/ReplicaSceneTest.cpp b/src/tests/ReplicaSceneTest.cpp index 463cbb12c0..774b1968b6 100644 --- a/src/tests/ReplicaSceneTest.cpp +++ b/src/tests/ReplicaSceneTest.cpp @@ -6,8 +6,6 @@ #include #include -#include -#include #include #include @@ -160,7 +158,7 @@ void ReplicaSceneTest::testSemanticSceneLoading() { CORRADE_VERIFY(obj12->category()); CORRADE_COMPARE(obj12->category()->index(), 13); CORRADE_COMPARE(obj12->category()->name(), "book"); -} // namespace +} // ReplicaSceneTest::testSemanticSceneLoading void ReplicaSceneTest::testSemanticSceneDescriptorReplicaCAD() { if (!Cr::Utility::Path::exists(replicaCAD)) { diff --git a/src/tests/SimTest.cpp b/src/tests/SimTest.cpp index 2dc3554fc2..967d91a617 100644 --- a/src/tests/SimTest.cpp +++ b/src/tests/SimTest.cpp @@ -8,7 +8,6 @@ #include #include #include -#include #include #include #include @@ -64,6 +63,12 @@ const std::string physicsConfigFile = Cr::Utility::Path::join(TEST_ASSETS, "testing.physics_config.json"); const std::string screenshotDir = Cr::Utility::Path::join(TEST_ASSETS, "screenshots/"); +const std::string nestedBoxPath = + Cr::Utility::Path::join(TEST_ASSETS, "objects/nested_box"); + +const std::string nestedBoxConfigPath = + Cr::Utility::Path::join(TEST_ASSETS, + "objects/nested_box.object_config.json"); struct SimTest : Cr::TestSuite::Tester { explicit SimTest(); @@ -89,8 +94,7 @@ struct SimTest : Cr::TestSuite::Tester { auto sim = Simulator::create_unique(simConfig); auto objAttrMgr = sim->getObjectAttributesManager(); - objAttrMgr->loadAllJSONConfigsFromPath( - Cr::Utility::Path::join(TEST_ASSETS, "objects/nested_box"), true); + objAttrMgr->loadAllJSONConfigsFromPath(nestedBoxPath, true); sim->setLightSetup(self.lightSetup1, "custom_lighting_1"); sim->setLightSetup(self.lightSetup2, "custom_lighting_2"); @@ -119,8 +123,7 @@ struct SimTest : Cr::TestSuite::Tester { MetadataMediator::ptr MM = MetadataMediator::create(simConfig); auto sim = Simulator::create_unique(simConfig, MM); auto objAttrMgr = sim->getObjectAttributesManager(); - objAttrMgr->loadAllJSONConfigsFromPath( - Cr::Utility::Path::join(TEST_ASSETS, "objects/nested_box"), true); + objAttrMgr->loadAllJSONConfigsFromPath(nestedBoxPath, true); sim->setLightSetup(self.lightSetup1, "custom_lighting_1"); sim->setLightSetup(self.lightSetup2, "custom_lighting_2"); @@ -754,8 +757,7 @@ void SimTest::addObjectByHandle() { CORRADE_COMPARE(obj, nullptr); // pass valid object_config.json filepath as handle to addObjectByHandle - const auto validHandle = Cr::Utility::Path::join( - TEST_ASSETS, "objects/nested_box.object_config.json"); + const auto validHandle = nestedBoxConfigPath; obj = rigidObjMgr->addObjectByHandle(validHandle); CORRADE_VERIFY(obj->isAlive()); CORRADE_VERIFY(obj->getID() != esp::ID_UNDEFINED); @@ -804,8 +806,7 @@ void SimTest::addObjectInvertedScale() { agent->setInitialState(AgentState{}); // Add 2 objects and take initial non-negative scaled observation - const auto objHandle = Cr::Utility::Path::join( - TEST_ASSETS, "objects/nested_box.object_config.json"); + const auto objHandle = nestedBoxConfigPath; Observation expectedObservation; addObjectsAndMakeObservation(*simulator, *pinholeCameraSpec, objHandle, @@ -1102,15 +1103,15 @@ void SimTest::testArticulatedObjectSkinned() { const auto linkIds = ao->getLinkIdsWithBase(); auto linkA = ao->getLink(linkIds[0]); - CORRADE_VERIFY(linkA->linkName == "A"); + CORRADE_COMPARE(linkA->linkName, "A"); auto linkB = ao->getLink(linkIds[1]); - CORRADE_VERIFY(linkB->linkName == "B"); + CORRADE_COMPARE(linkB->linkName, "B"); auto linkC = ao->getLink(linkIds[2]); - CORRADE_VERIFY(linkC->linkName == "C"); + CORRADE_COMPARE(linkC->linkName, "C"); auto linkD = ao->getLink(linkIds[3]); - CORRADE_VERIFY(linkD->linkName == "D"); + CORRADE_COMPARE(linkD->linkName, "D"); auto linkE = ao->getLink(linkIds[4]); - CORRADE_VERIFY(linkE->linkName == "E"); + CORRADE_COMPARE(linkE->linkName, "E"); ao->setTranslation({1.f, -3.f, -6.f}); diff --git a/src/utils/datatool/Mp3dInstanceMeshData.cpp b/src/utils/datatool/Mp3dInstanceMeshData.cpp index 10304ec908..d47584cdfd 100644 --- a/src/utils/datatool/Mp3dInstanceMeshData.cpp +++ b/src/utils/datatool/Mp3dInstanceMeshData.cpp @@ -89,7 +89,7 @@ bool Mp3dInstanceMeshData::loadMp3dPLY(const std::string& plyFile) { Mn::Vector3 position; Mn::Vector3 normal; Mn::Vector2 texCoords; - Mn::Vector3ui rgb; + Mn::Vector3ub rgb; ifs.read(reinterpret_cast(position.data()), 3 * sizeof(float)); ifs.read(reinterpret_cast(normal.data()), 3 * sizeof(float)); @@ -101,7 +101,7 @@ bool Mp3dInstanceMeshData::loadMp3dPLY(const std::string& plyFile) { for (int i = 0; i < nFace; ++i) { uint8_t nIndices = 0; - Mn::Vector3i indices; + Mn::Vector3ui indices; int32_t materialId = 0; int32_t segmentId = 0; int32_t categoryId = 0; diff --git a/src/utils/viewer/viewer.cpp b/src/utils/viewer/viewer.cpp index e11ab0eb29..c1d7db357a 100644 --- a/src/utils/viewer/viewer.cpp +++ b/src/utils/viewer/viewer.cpp @@ -687,7 +687,7 @@ void addSensors(esp::agent::AgentConfiguration& agentConfig, bool isOrtho) { } spec->position = {0.0f, rgbSensorHeight, 0.0f}; spec->orientation = {0, 0, 0}; - spec->resolution = Mn::Vector2i(viewportSize[1], viewportSize[0]); + spec->resolution = viewportSize.flipped(); }; // add the camera color sensor // for historical reasons, we call it "rgba_camera" @@ -716,7 +716,7 @@ void addSensors(esp::agent::AgentConfiguration& agentConfig, bool isOrtho) { } spec->sensorSubType = esp::sensor::SensorSubType::Fisheye; spec->fisheyeModelType = modelType; - spec->resolution = Mn::Vector2i(viewportSize[1], viewportSize[0]); + spec->resolution = viewportSize.flipped(); // default viewport size: 1600 x 1200 spec->principalPointOffset = Mn::Vector2(viewportSize[0] / 2, viewportSize[1] / 2); @@ -761,7 +761,7 @@ void addSensors(esp::agent::AgentConfiguration& agentConfig, bool isOrtho) { spec->channels = 1; } spec->sensorSubType = esp::sensor::SensorSubType::Equirectangular; - spec->resolution = Mn::Vector2i(viewportSize[1], viewportSize[0]); + spec->resolution = viewportSize.flipped(); }; // add the equirectangular sensor addEquirectangularSensor("rgba_equirectangular", @@ -2258,7 +2258,7 @@ void Viewer::keyPressEvent(KeyEvent& event) { break; case KeyEvent::Key::Nine: if (simulator_->getPathFinder()->isLoaded()) { - const auto position = + const Mn::Vector3 position = simulator_->getPathFinder()->getRandomNavigablePoint(); agentBodyNode_->setTranslation(Mn::Vector3(position)); }