diff --git a/src/esp/sensor/AudioSensor.cpp b/src/esp/sensor/AudioSensor.cpp index 91afe8cb86..0f391c943b 100644 --- a/src/esp/sensor/AudioSensor.cpp +++ b/src/esp/sensor/AudioSensor.cpp @@ -78,7 +78,7 @@ void AudioSensor::reset() { impulseResponse_.clear(); } -void AudioSensor::setAudioSourceTransform(const Magnum::Vector3& sourcePos) { +void AudioSensor::setAudioSourceTransform(const Mn::Vector3& sourcePos) { ESP_DEBUG() << logHeader_ << "Setting the audio source position : " << sourcePos << "]"; lastSourcePos_ = sourcePos; @@ -86,9 +86,8 @@ void AudioSensor::setAudioSourceTransform(const Magnum::Vector3& sourcePos) { newSource_ = true; } -void AudioSensor::setAudioListenerTransform( - const Magnum::Vector3& agentPos, - const Magnum::Vector4& agentRotQuat) { +void AudioSensor::setAudioListenerTransform(const Mn::Vector3& agentPos, + const Mn::Vector4& agentRotQuat) { ESP_DEBUG() << logHeader_ << "Setting the agent transform : position [" << agentPos << "], rotQuat[" << agentRotQuat << "]"; diff --git a/src/esp/sensor/AudioSensor.h b/src/esp/sensor/AudioSensor.h index f55a9db740..575fbe29e3 100644 --- a/src/esp/sensor/AudioSensor.h +++ b/src/esp/sensor/AudioSensor.h @@ -68,15 +68,15 @@ class AudioSensor : public Sensor { * @brief Set the audio source transform * @param sourcePos = vec3 source position * */ - void setAudioSourceTransform(const Magnum::Vector3& sourcePos); + void setAudioSourceTransform(const Mn::Vector3& sourcePos); /** * @brief Set the audio listener position and orientation * @param agentPos = vec3 agent position * @param agentRotQuat = vec4 agent rotation quaternion * */ - void setAudioListenerTransform(const Magnum::Vector3& agentPos, - const Magnum::Vector4& agentRotQuat); + void setAudioListenerTransform(const Mn::Vector3& agentPos, + const Mn::Vector4& agentRotQuat); /** * @brief Run the audio simulation. This will run the RLRAudioPropagation code @@ -146,11 +146,11 @@ class AudioSensor : public Sensor { //! track the number of simulations std::int32_t currentSimCount_ = -1; //! track the source position - Magnum::Vector3 lastSourcePos_; + Mn::Vector3 lastSourcePos_; //! track the agent orientation - Magnum::Vector3 lastAgentPos_; + Mn::Vector3 lastAgentPos_; //! track the agent rotation - Magnum::Vector4 lastAgentRot_; + Mn::Vector4 lastAgentRot_; //! audio materials json path std::string audioMaterialsJSON_; diff --git a/src/esp/sensor/CameraSensor.cpp b/src/esp/sensor/CameraSensor.cpp index 9e1f53bd2d..d5812d2229 100644 --- a/src/esp/sensor/CameraSensor.cpp +++ b/src/esp/sensor/CameraSensor.cpp @@ -69,8 +69,8 @@ Mn::Matrix4 CameraSensorSpec::projectionMatrix() const { CameraSensor::CameraSensor(scene::SceneNode& cameraNode, const CameraSensorSpec::ptr& spec) : VisualSensor(cameraNode, spec), - baseProjMatrix_(Magnum::Math::IdentityInit), - zoomMatrix_(Magnum::Math::IdentityInit), + baseProjMatrix_(Mn::Math::IdentityInit), + zoomMatrix_(Mn::Math::IdentityInit), renderCamera_(new gfx::RenderCamera(cameraNode, visualSensorSpec_->semanticTarget)) { // Sanity check @@ -177,8 +177,7 @@ bool CameraSensor::drawObservation(sim::Simulator& sim) { return true; } -Corrade::Containers::Optional CameraSensor::depthUnprojection() - const { +Cr::Containers::Optional CameraSensor::depthUnprojection() const { // projectionMatrix_ is managed by implementation class and is set whenever // quantities change. return {gfx_batch::calculateDepthUnprojection(projectionMatrix_)}; diff --git a/src/esp/sensor/CameraSensor.h b/src/esp/sensor/CameraSensor.h index 307f81ca4f..edfb04faaf 100644 --- a/src/esp/sensor/CameraSensor.h +++ b/src/esp/sensor/CameraSensor.h @@ -21,7 +21,7 @@ struct CameraSensorSpec : public VisualSensorSpec { CameraSensorSpec(); void sanityCheck() const override; bool operator==(const CameraSensorSpec& a) const; - Magnum::Matrix4 projectionMatrix() const; + Mn::Matrix4 projectionMatrix() const; ESP_SMART_POINTERS(CameraSensorSpec) }; @@ -50,8 +50,7 @@ class CameraSensor : public VisualSensor { * perspective projection model. * See @ref gfx::calculateDepthUnprojection */ - Corrade::Containers::Optional depthUnprojection() - const override; + Cr::Containers::Optional depthUnprojection() const override; /** * @brief Draw an observation to the frame buffer using simulator's renderer @@ -66,8 +65,7 @@ class CameraSensor : public VisualSensor { * @param factor Modification amount. */ void modifyZoom(float factor) { - zoomMatrix_ = - Magnum::Matrix4::scaling({factor, factor, 1.0f}) * zoomMatrix_; + zoomMatrix_ = Mn::Matrix4::scaling({factor, factor, 1.0f}) * zoomMatrix_; recomputeProjectionMatrix(); } @@ -76,7 +74,7 @@ class CameraSensor : public VisualSensor { * values. */ void resetZoom() { - zoomMatrix_ = Magnum::Matrix4(Magnum::Math::IdentityInit); + zoomMatrix_ = Mn::Matrix4(Mn::Math::IdentityInit); recomputeProjectionMatrix(); } @@ -197,17 +195,17 @@ class CameraSensor : public VisualSensor { * @brief This camera's projection matrix. Should be recomputed every time * size changes. */ - Magnum::Matrix4 projectionMatrix_; + Mn::Matrix4 projectionMatrix_; /** * @brief A base projection matrix based on camera's type and display size. */ - Magnum::Matrix4 baseProjMatrix_; + Mn::Matrix4 baseProjMatrix_; /** * @brief A matrix to determine the zoom for the projection. */ - Magnum::Matrix4 zoomMatrix_; + Mn::Matrix4 zoomMatrix_; /** @brief size of near plane */ diff --git a/src/esp/sensor/CubeMapSensorBase.cpp b/src/esp/sensor/CubeMapSensorBase.cpp index 45f4f6ab59..4f317c50d6 100644 --- a/src/esp/sensor/CubeMapSensorBase.cpp +++ b/src/esp/sensor/CubeMapSensorBase.cpp @@ -8,9 +8,6 @@ #include #include -namespace Mn = Magnum; -namespace Cr = Corrade; - namespace esp { namespace sensor { @@ -28,11 +25,11 @@ void CubeMapSensorBaseSpec::sanityCheck() const { } } -int computeCubemapSize(const Magnum::Vector2i& resolution, +int computeCubemapSize(const Mn::Vector2i& resolution, const Cr::Containers::Optional& cubemapSize) { int size = (resolution[0] < resolution[1] ? resolution[0] : resolution[1]); // if user sets the size of the cubemap, use it - if (cubemapSize != Corrade::Containers::NullOpt) { + if (cubemapSize != Cr::Containers::NullOpt) { size = *cubemapSize; } return size; diff --git a/src/esp/sensor/CubeMapSensorBase.h b/src/esp/sensor/CubeMapSensorBase.h index eb1beafae1..0c7efdddac 100644 --- a/src/esp/sensor/CubeMapSensorBase.h +++ b/src/esp/sensor/CubeMapSensorBase.h @@ -26,7 +26,7 @@ struct CubeMapSensorBaseSpec : public VisualSensorSpec { /** * @brief the size of the cubemap */ - Corrade::Containers::Optional cubemapSize = Corrade::Containers::NullOpt; + Cr::Containers::Optional cubemapSize = Cr::Containers::NullOpt; /** * @brief Constructor @@ -75,22 +75,22 @@ class CubeMapSensorBase : public VisualSensor { // raw pointer only, we can create it but let magnum to handle the memory // recycling when releasing it. gfx::CubeMapCamera* cubeMapCamera_; - Corrade::Containers::Optional cubeMap_; + Cr::Containers::Optional cubeMap_; // a big triangles that covers the whole screen - Magnum::GL::Mesh mesh_; + Mn::GL::Mesh mesh_; // cubemap shader resource manager, which manages different shaders such as // DoubleSphereCameraShader, FieldOfViewCameraShader (TODO), // EquiRectangularShader ... - Magnum::ResourceManager cubeMapShaderBaseManager_; + Mn::ResourceManager cubeMapShaderBaseManager_; gfx::CubeMapShaderBase::Flags cubeMapShaderBaseFlags_{}; - virtual Magnum::ResourceKey getShaderKey() = 0; + virtual Mn::ResourceKey getShaderKey() = 0; template - Magnum::Resource getShader(); + Mn::Resource getShader(); /** * @brief render the sense into cubemap textures @@ -108,8 +108,8 @@ class CubeMapSensorBase : public VisualSensor { }; template -Magnum::Resource CubeMapSensorBase::getShader() { - Magnum::Resource shader = +Mn::Resource CubeMapSensorBase::getShader() { + Mn::Resource shader = cubeMapShaderBaseManager_.get(getShaderKey()); if (!shader) { cubeMapShaderBaseManager_.set( diff --git a/src/esp/sensor/EquirectangularSensor.cpp b/src/esp/sensor/EquirectangularSensor.cpp index 4853058d37..d32a460273 100644 --- a/src/esp/sensor/EquirectangularSensor.cpp +++ b/src/esp/sensor/EquirectangularSensor.cpp @@ -9,9 +9,6 @@ #include "esp/gfx/EquirectangularShader.h" #include "esp/sim/Simulator.h" -namespace Mn = Magnum; -namespace Cr = Corrade; - namespace esp { namespace sensor { @@ -40,7 +37,7 @@ bool EquirectangularSensor::drawObservation(sim::Simulator& sim) { return false; } renderToCubemapTexture(sim); - Magnum::Resource shader = + Mn::Resource shader = getShader(); (*shader).setViewportSize(equirectangularSensorSpec_->resolution); diff --git a/src/esp/sensor/EquirectangularSensor.h b/src/esp/sensor/EquirectangularSensor.h index 512e68000c..88f242353d 100644 --- a/src/esp/sensor/EquirectangularSensor.h +++ b/src/esp/sensor/EquirectangularSensor.h @@ -73,7 +73,7 @@ class EquirectangularSensor : public CubeMapSensorBase { protected: EquirectangularSensorSpec::ptr equirectangularSensorSpec_ = std::dynamic_pointer_cast(spec_); - Magnum::ResourceKey getShaderKey() override; + Mn::ResourceKey getShaderKey() override; ESP_SMART_POINTERS(EquirectangularSensor) }; diff --git a/src/esp/sensor/FisheyeSensor.cpp b/src/esp/sensor/FisheyeSensor.cpp index 86dc85cdf0..02b040bd17 100644 --- a/src/esp/sensor/FisheyeSensor.cpp +++ b/src/esp/sensor/FisheyeSensor.cpp @@ -8,9 +8,6 @@ #include #include -namespace Mn = Magnum; -namespace Cr = Corrade; - namespace esp { namespace sensor { @@ -48,7 +45,7 @@ void specSanityCheck(FisheyeSensorSpec* spec) { actualSpec->sanityCheck(); } -Magnum::Vector2 computePrincipalPointOffset(const FisheyeSensorSpec& spec) { +Mn::Vector2 computePrincipalPointOffset(const FisheyeSensorSpec& spec) { if (bool(spec.principalPointOffset)) { return *spec.principalPointOffset; } @@ -86,7 +83,7 @@ bool FisheyeSensor::drawObservation(sim::Simulator& sim) { switch (fisheyeSensorSpec_->fisheyeModelType) { case FisheyeSensorModelType::DoubleSphere: { - Magnum::Resource + Mn::Resource shader = getShader(); auto& actualSpec = static_cast(*fisheyeSensorSpec_); diff --git a/src/esp/sensor/FisheyeSensor.h b/src/esp/sensor/FisheyeSensor.h index 9e00f927ac..ed6f74d5d3 100644 --- a/src/esp/sensor/FisheyeSensor.h +++ b/src/esp/sensor/FisheyeSensor.h @@ -24,7 +24,7 @@ class Simulator; namespace sensor { -enum class FisheyeSensorModelType : Magnum::UnsignedInt { +enum class FisheyeSensorModelType : Mn::UnsignedInt { // Vladyslav Usenko, Nikolaus Demmel and Daniel Cremers: The Double Sphere // Camera Model, The International Conference on 3D Vision (3DV), 2018 @@ -46,13 +46,13 @@ struct FisheyeSensorSpec : public CubeMapSensorBaseSpec { * In practice, fx and fy can differ for a number of reasons. See * details here: http://ksimek.github.io/2013/08/13/intrinsic/ */ - Magnum::Vector2 focalLength; + Mn::Vector2 focalLength; /** * @brief Principal Point Offset in pixel, cx, cy, location of the principal * point relative to the image plane's origin. None will place it in the * middle of the image (height/2, width/2). */ - Corrade::Containers::Optional principalPointOffset; + Cr::Containers::Optional principalPointOffset; /** * @brief Constructor @@ -127,7 +127,7 @@ class FisheyeSensor : public CubeMapSensorBase { protected: FisheyeSensorSpec::ptr fisheyeSensorSpec_ = std::dynamic_pointer_cast(spec_); - Magnum::ResourceKey getShaderKey() override; + Mn::ResourceKey getShaderKey() override; ESP_SMART_POINTERS(FisheyeSensor) }; diff --git a/src/esp/sensor/Sensor.cpp b/src/esp/sensor/Sensor.cpp index 366c45ed9a..82b68eab47 100644 --- a/src/esp/sensor/Sensor.cpp +++ b/src/esp/sensor/Sensor.cpp @@ -8,7 +8,6 @@ #include -namespace Mn = Magnum; namespace esp { namespace sensor { @@ -44,7 +43,7 @@ void SensorSpec::sanityCheck() const { } Sensor::Sensor(scene::SceneNode& node, SensorSpec::ptr spec) - : Magnum::SceneGraph::AbstractFeature3D{node}, spec_(std::move(spec)) { + : Mn::SceneGraph::AbstractFeature3D{node}, spec_(std::move(spec)) { CORRADE_ASSERT(node.children().first() == nullptr, "Sensor::Sensor(): Cannot attach a sensor to a non-LEAF node. " "The number of children of this node is not zero.", ); @@ -71,11 +70,11 @@ Sensor::~Sensor() { scene::SceneNode& Sensor::object() { return static_cast( - Magnum::SceneGraph::AbstractFeature3D::object()); + Mn::SceneGraph::AbstractFeature3D::object()); } const scene::SceneNode& Sensor::object() const { return static_cast( - Magnum::SceneGraph::AbstractFeature3D::object()); + Mn::SceneGraph::AbstractFeature3D::object()); } void Sensor::setTransformationFromSpec() { @@ -86,21 +85,21 @@ void Sensor::setTransformationFromSpec() { node().resetTransformation(); node().translate(spec_->position); - node().rotateX(Magnum::Rad(spec_->orientation[0])); - node().rotateY(Magnum::Rad(spec_->orientation[1])); - node().rotateZ(Magnum::Rad(spec_->orientation[2])); + node().rotateX(Mn::Rad(spec_->orientation[0])); + node().rotateY(Mn::Rad(spec_->orientation[1])); + node().rotateZ(Mn::Rad(spec_->orientation[2])); } SensorSuite::SensorSuite(scene::SceneNode& node) - : Magnum::SceneGraph::AbstractFeature3D{node} {} + : Mn::SceneGraph::AbstractFeature3D{node} {} scene::SceneNode& SensorSuite::object() { return static_cast( - Magnum::SceneGraph::AbstractFeature3D::object()); + Mn::SceneGraph::AbstractFeature3D::object()); } const scene::SceneNode& SensorSuite::object() const { return static_cast( - Magnum::SceneGraph::AbstractFeature3D::object()); + Mn::SceneGraph::AbstractFeature3D::object()); } void SensorSuite::add(sensor::Sensor& sensor) { diff --git a/src/esp/sensor/Sensor.h b/src/esp/sensor/Sensor.h index 55aac0ea3d..7545068d7a 100644 --- a/src/esp/sensor/Sensor.h +++ b/src/esp/sensor/Sensor.h @@ -6,12 +6,15 @@ #define ESP_SENSOR_SENSOR_H_ #include +#include #include #include "esp/core/Buffer.h" #include "esp/core/Esp.h" #include "esp/sensor/configure.h" +namespace Mn = Magnum; +namespace Cr = Corrade; namespace esp { namespace scene { class SceneNode; @@ -58,8 +61,8 @@ struct SensorSpec { std::string uuid = ""; SensorType sensorType = SensorType::Unspecified; SensorSubType sensorSubType = SensorSubType::Unspecified; - Magnum::Vector3 position = {0, 1.5, 0}; - Magnum::Vector3 orientation = {0, 0, 0}; + Mn::Vector3 position = {0, 1.5, 0}; + Mn::Vector3 orientation = {0, 0, 0}; std::string noiseModel = "None"; SensorSpec() = default; virtual ~SensorSpec() = default; @@ -86,7 +89,7 @@ struct ObservationSpace { }; // Represents a sensor that provides data from the environment -class Sensor : public Magnum::SceneGraph::AbstractFeature3D { +class Sensor : public Mn::SceneGraph::AbstractFeature3D { public: explicit Sensor(scene::SceneNode& node, SensorSpec::ptr spec); ~Sensor() override; @@ -173,7 +176,7 @@ class Sensor : public Magnum::SceneGraph::AbstractFeature3D { // Represents a set of sensors, with each sensor being identified through a // unique id -class SensorSuite : public Magnum::SceneGraph::AbstractFeature3D { +class SensorSuite : public Mn::SceneGraph::AbstractFeature3D { public: explicit SensorSuite(scene::SceneNode& node); diff --git a/src/esp/sensor/VisualSensor.cpp b/src/esp/sensor/VisualSensor.cpp index 7538f548d4..70c5d833e7 100644 --- a/src/esp/sensor/VisualSensor.cpp +++ b/src/esp/sensor/VisualSensor.cpp @@ -110,16 +110,16 @@ void VisualSensor::readObservation(Observation& obs) { // TODO: have different classes for the different types of sensors // TODO: do we need to flip axis? if (visualSensorSpec_->sensorType == SensorType::Semantic) { - renderTarget().readFrameObjectId(Magnum::MutableImageView2D{ - Magnum::PixelFormat::R32UI, renderTarget().framebufferSize(), + renderTarget().readFrameObjectId(Mn::MutableImageView2D{ + Mn::PixelFormat::R32UI, renderTarget().framebufferSize(), obs.buffer->data}); } else if (visualSensorSpec_->sensorType == SensorType::Depth) { - renderTarget().readFrameDepth(Magnum::MutableImageView2D{ - Magnum::PixelFormat::R32F, renderTarget().framebufferSize(), + renderTarget().readFrameDepth(Mn::MutableImageView2D{ + Mn::PixelFormat::R32F, renderTarget().framebufferSize(), obs.buffer->data}); } else { - renderTarget().readFrameRgba(Magnum::MutableImageView2D{ - Magnum::PixelFormat::RGBA8Unorm, renderTarget().framebufferSize(), + renderTarget().readFrameRgba(Mn::MutableImageView2D{ + Mn::PixelFormat::RGBA8Unorm, renderTarget().framebufferSize(), obs.buffer->data}); } } diff --git a/src/esp/sensor/VisualSensor.h b/src/esp/sensor/VisualSensor.h index 4321fa340e..d4bedf5cc3 100644 --- a/src/esp/sensor/VisualSensor.h +++ b/src/esp/sensor/VisualSensor.h @@ -15,9 +15,6 @@ #include "esp/gfx/RenderCamera.h" #include "esp/sensor/Sensor.h" -namespace Mn = Magnum; -namespace Cr = Corrade; - namespace esp { namespace gfx { class RenderTarget; @@ -81,7 +78,7 @@ class VisualSensor : public Sensor { * @brief Return the size of the framebuffer corresponding to the sensor's * resolution as a [W, H] Vector2i */ - Magnum::Vector2i framebufferSize() const { + Mn::Vector2i framebufferSize() const { // NB: The sensor's resolution is in H x W format as that more cleanly // corresponds to the practice of treating images as arrays that is used in // modern CV and DL. However, graphics frameworks expect W x H format for @@ -103,8 +100,7 @@ class VisualSensor : public Sensor { /** * @brief Returns the parameters needed to unproject depth for the sensor. */ - virtual Corrade::Containers::Optional depthUnprojection() - const; + virtual Cr::Containers::Optional depthUnprojection() const; /** * @brief Checks to see if this sensor has a RenderTarget bound or not @@ -173,7 +169,7 @@ class VisualSensor : public Sensor { visualSensorSpec_->resolution = {height, width}; } - void setResolution(const Magnum::Vector2i& resolution) { + void setResolution(const Mn::Vector2i& resolution) { CORRADE_ASSERT(resolution[0] > 0 && resolution[1] > 0, "VisualSensor::setResolution(): resolution height and " "width must be greater than 0", ); @@ -250,8 +246,8 @@ class VisualSensor : public Sensor { protected: VisualSensor& visualSensor_; sim::Simulator& sim_; - Corrade::Containers::Optional relativeTransformBackup_ = - Corrade::Containers::NullOpt; + Cr::Containers::Optional relativeTransformBackup_ = + Cr::Containers::NullOpt; scene::SceneNode* semanticSensorParentNodeBackup_ = nullptr; }; diff --git a/src/esp/sensor/sensorWrappers/ManagedAudioSensor.h b/src/esp/sensor/sensorWrappers/ManagedAudioSensor.h index dc47c3a7d8..583f362d16 100644 --- a/src/esp/sensor/sensorWrappers/ManagedAudioSensor.h +++ b/src/esp/sensor/sensorWrappers/ManagedAudioSensor.h @@ -8,11 +8,9 @@ #include #include +#include "ManagedSensorTemplates.h" #include "esp/sensor/AudioSensor.h" -#include "esp/sensor/sensorWrappers/ManagedSensorTemplates.h" -namespace Cr = Corrade; -namespace Mn = Magnum; namespace esp { namespace sensor { diff --git a/src/esp/sensor/sensorWrappers/ManagedSensorBase.h b/src/esp/sensor/sensorWrappers/ManagedSensorBase.h index f3dfdde3ce..88f293fbd1 100644 --- a/src/esp/sensor/sensorWrappers/ManagedSensorBase.h +++ b/src/esp/sensor/sensorWrappers/ManagedSensorBase.h @@ -11,8 +11,6 @@ #include "esp/core/managedContainers/AbstractManagedObject.h" #include "esp/sensor/Sensor.h" -namespace Cr = Corrade; -namespace Mn = Magnum; namespace esp { namespace sensor { diff --git a/src/esp/sensor/sensorWrappers/ManagedSensorTemplates.h b/src/esp/sensor/sensorWrappers/ManagedSensorTemplates.h index 4750a78747..ff8374227e 100644 --- a/src/esp/sensor/sensorWrappers/ManagedSensorTemplates.h +++ b/src/esp/sensor/sensorWrappers/ManagedSensorTemplates.h @@ -11,8 +11,6 @@ #include "ManagedSensorBase.h" #include "esp/sensor/Sensor.h" -namespace Cr = Corrade; -namespace Mn = Magnum; namespace esp { namespace sensor {