Skip to content

Commit

Permalink
--cleanup magnum namespace aliases
Browse files Browse the repository at this point in the history
  • Loading branch information
jturner65 committed Dec 27, 2024
1 parent f83fa04 commit 5e66f99
Show file tree
Hide file tree
Showing 17 changed files with 64 additions and 85 deletions.
7 changes: 3 additions & 4 deletions src/esp/sensor/AudioSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,17 +78,16 @@ 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;
// track if the source has changed
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 << "]";

Expand Down
12 changes: 6 additions & 6 deletions src/esp/sensor/AudioSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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_;

Expand Down
7 changes: 3 additions & 4 deletions src/esp/sensor/CameraSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -177,8 +177,7 @@ bool CameraSensor::drawObservation(sim::Simulator& sim) {
return true;
}

Corrade::Containers::Optional<Magnum::Vector2> CameraSensor::depthUnprojection()
const {
Cr::Containers::Optional<Mn::Vector2> CameraSensor::depthUnprojection() const {
// projectionMatrix_ is managed by implementation class and is set whenever
// quantities change.
return {gfx_batch::calculateDepthUnprojection(projectionMatrix_)};
Expand Down
16 changes: 7 additions & 9 deletions src/esp/sensor/CameraSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
};

Expand Down Expand Up @@ -50,8 +50,7 @@ class CameraSensor : public VisualSensor {
* perspective projection model.
* See @ref gfx::calculateDepthUnprojection
*/
Corrade::Containers::Optional<Magnum::Vector2> depthUnprojection()
const override;
Cr::Containers::Optional<Mn::Vector2> depthUnprojection() const override;

/**
* @brief Draw an observation to the frame buffer using simulator's renderer
Expand All @@ -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();
}

Expand All @@ -76,7 +74,7 @@ class CameraSensor : public VisualSensor {
* values.
*/
void resetZoom() {
zoomMatrix_ = Magnum::Matrix4(Magnum::Math::IdentityInit);
zoomMatrix_ = Mn::Matrix4(Mn::Math::IdentityInit);
recomputeProjectionMatrix();
}

Expand Down Expand Up @@ -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
*/
Expand Down
7 changes: 2 additions & 5 deletions src/esp/sensor/CubeMapSensorBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,6 @@
#include <Corrade/Utility/Assert.h>
#include <Corrade/Utility/FormatStl.h>

namespace Mn = Magnum;
namespace Cr = Corrade;

namespace esp {
namespace sensor {

Expand All @@ -28,11 +25,11 @@ void CubeMapSensorBaseSpec::sanityCheck() const {
}
}

int computeCubemapSize(const Magnum::Vector2i& resolution,
int computeCubemapSize(const Mn::Vector2i& resolution,
const Cr::Containers::Optional<int>& 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;
Expand Down
16 changes: 8 additions & 8 deletions src/esp/sensor/CubeMapSensorBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ struct CubeMapSensorBaseSpec : public VisualSensorSpec {
/**
* @brief the size of the cubemap
*/
Corrade::Containers::Optional<int> cubemapSize = Corrade::Containers::NullOpt;
Cr::Containers::Optional<int> cubemapSize = Cr::Containers::NullOpt;

/**
* @brief Constructor
Expand Down Expand Up @@ -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<esp::gfx::CubeMap> cubeMap_;
Cr::Containers::Optional<esp::gfx::CubeMap> 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<gfx::CubeMapShaderBase> cubeMapShaderBaseManager_;
Mn::ResourceManager<gfx::CubeMapShaderBase> cubeMapShaderBaseManager_;

gfx::CubeMapShaderBase::Flags cubeMapShaderBaseFlags_{};

virtual Magnum::ResourceKey getShaderKey() = 0;
virtual Mn::ResourceKey getShaderKey() = 0;

template <typename T>
Magnum::Resource<gfx::CubeMapShaderBase, T> getShader();
Mn::Resource<gfx::CubeMapShaderBase, T> getShader();

/**
* @brief render the sense into cubemap textures
Expand All @@ -108,8 +108,8 @@ class CubeMapSensorBase : public VisualSensor {
};

template <typename T>
Magnum::Resource<gfx::CubeMapShaderBase, T> CubeMapSensorBase::getShader() {
Magnum::Resource<gfx::CubeMapShaderBase, T> shader =
Mn::Resource<gfx::CubeMapShaderBase, T> CubeMapSensorBase::getShader() {
Mn::Resource<gfx::CubeMapShaderBase, T> shader =
cubeMapShaderBaseManager_.get<gfx::CubeMapShaderBase, T>(getShaderKey());
if (!shader) {
cubeMapShaderBaseManager_.set<gfx::CubeMapShaderBase>(
Expand Down
5 changes: 1 addition & 4 deletions src/esp/sensor/EquirectangularSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,6 @@
#include "esp/gfx/EquirectangularShader.h"
#include "esp/sim/Simulator.h"

namespace Mn = Magnum;
namespace Cr = Corrade;

namespace esp {
namespace sensor {

Expand Down Expand Up @@ -40,7 +37,7 @@ bool EquirectangularSensor::drawObservation(sim::Simulator& sim) {
return false;
}
renderToCubemapTexture(sim);
Magnum::Resource<gfx::CubeMapShaderBase, gfx::EquirectangularShader> shader =
Mn::Resource<gfx::CubeMapShaderBase, gfx::EquirectangularShader> shader =
getShader<gfx::EquirectangularShader>();

(*shader).setViewportSize(equirectangularSensorSpec_->resolution);
Expand Down
2 changes: 1 addition & 1 deletion src/esp/sensor/EquirectangularSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class EquirectangularSensor : public CubeMapSensorBase {
protected:
EquirectangularSensorSpec::ptr equirectangularSensorSpec_ =
std::dynamic_pointer_cast<EquirectangularSensorSpec>(spec_);
Magnum::ResourceKey getShaderKey() override;
Mn::ResourceKey getShaderKey() override;
ESP_SMART_POINTERS(EquirectangularSensor)
};

Expand Down
7 changes: 2 additions & 5 deletions src/esp/sensor/FisheyeSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,6 @@
#include <Corrade/Utility/Assert.h>
#include <Corrade/Utility/FormatStl.h>

namespace Mn = Magnum;
namespace Cr = Corrade;

namespace esp {
namespace sensor {

Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -86,7 +83,7 @@ bool FisheyeSensor::drawObservation(sim::Simulator& sim) {

switch (fisheyeSensorSpec_->fisheyeModelType) {
case FisheyeSensorModelType::DoubleSphere: {
Magnum::Resource<gfx::CubeMapShaderBase, gfx::DoubleSphereCameraShader>
Mn::Resource<gfx::CubeMapShaderBase, gfx::DoubleSphereCameraShader>
shader = getShader<gfx::DoubleSphereCameraShader>();
auto& actualSpec =
static_cast<FisheyeSensorDoubleSphereSpec&>(*fisheyeSensorSpec_);
Expand Down
8 changes: 4 additions & 4 deletions src/esp/sensor/FisheyeSensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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<Magnum::Vector2> principalPointOffset;
Cr::Containers::Optional<Mn::Vector2> principalPointOffset;

/**
* @brief Constructor
Expand Down Expand Up @@ -127,7 +127,7 @@ class FisheyeSensor : public CubeMapSensorBase {
protected:
FisheyeSensorSpec::ptr fisheyeSensorSpec_ =
std::dynamic_pointer_cast<FisheyeSensorSpec>(spec_);
Magnum::ResourceKey getShaderKey() override;
Mn::ResourceKey getShaderKey() override;

ESP_SMART_POINTERS(FisheyeSensor)
};
Expand Down
19 changes: 9 additions & 10 deletions src/esp/sensor/Sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@

#include <utility>

namespace Mn = Magnum;
namespace esp {
namespace sensor {

Expand Down Expand Up @@ -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.", );
Expand All @@ -71,11 +70,11 @@ Sensor::~Sensor() {

scene::SceneNode& Sensor::object() {
return static_cast<scene::SceneNode&>(
Magnum::SceneGraph::AbstractFeature3D::object());
Mn::SceneGraph::AbstractFeature3D::object());
}
const scene::SceneNode& Sensor::object() const {
return static_cast<const scene::SceneNode&>(
Magnum::SceneGraph::AbstractFeature3D::object());
Mn::SceneGraph::AbstractFeature3D::object());
}

void Sensor::setTransformationFromSpec() {
Expand All @@ -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<scene::SceneNode&>(
Magnum::SceneGraph::AbstractFeature3D::object());
Mn::SceneGraph::AbstractFeature3D::object());
}
const scene::SceneNode& SensorSuite::object() const {
return static_cast<const scene::SceneNode&>(
Magnum::SceneGraph::AbstractFeature3D::object());
Mn::SceneGraph::AbstractFeature3D::object());
}

void SensorSuite::add(sensor::Sensor& sensor) {
Expand Down
Loading

0 comments on commit 5e66f99

Please sign in to comment.