Skip to content

Commit

Permalink
--set up base class and class templates for wrappers.
Browse files Browse the repository at this point in the history
  • Loading branch information
jturner65 committed Dec 19, 2024
1 parent 8c0358d commit de8a096
Show file tree
Hide file tree
Showing 8 changed files with 323 additions and 46 deletions.
3 changes: 2 additions & 1 deletion src/esp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -469,7 +469,8 @@ set(
sensor/EquirectangularSensor.h
sensor/FisheyeSensor.cpp
sensor/FisheyeSensor.h
sensor/sensorManagers/SensorBaseManager.h
sensor/sensorManagers/SensorManager.cpp
sensor/sensorManagers/SensorManager.h
sensor/sensorWrappers/ManagedSensorBase.h
sensor/Sensor.cpp
sensor/Sensor.h
Expand Down
15 changes: 15 additions & 0 deletions src/esp/sensor/Sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,16 @@ class Sensor : public Magnum::SceneGraph::AbstractFeature3D {
*/
void setTransformationFromSpec();

/**
* @brief The unique handle assigned to this sensor at creation
*/
std::string getSensorHandle() const { return sensorHandle_; }

/**
* @brief The unique ID assigned to this sensor at creation
*/
int getSensorID() const { return sensorId_; }

/**
* @brief Draws an observation to the frame buffer using simulator's renderer,
* then reads the observation to the sensor's memory buffer
Expand Down Expand Up @@ -150,6 +160,11 @@ class Sensor : public Magnum::SceneGraph::AbstractFeature3D {
virtual bool displayObservation(sim::Simulator& sim) = 0;

protected:
// unique handle for sensor built when sensor is constructed.
std::string sensorHandle_;

// unique id for sensor set when sensor is built.
int sensorId_ = ID_UNDEFINED;
SensorSpec::ptr spec_ = nullptr;
core::Buffer::ptr buffer_ = nullptr;

Expand Down
2 changes: 1 addition & 1 deletion src/esp/sensor/sensorManagers/SensorBaseManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ class SensorBaseManager
managedSensorTypeConstructorMap_.find(sensorTypeName);
if (mgdSensorTypeCtorMapIter == managedSensorTypeConstructorMap_.end()) {
ESP_ERROR(Mn::Debug::Flag::NoSpace)
<< "<" << this->sensorType_ << "> Unknown constructor type "
<< "<" << this->objectType_ << "> Unknown constructor type "
<< sensorTypeName << ", so initNewObject aborted.";
return nullptr;
}
Expand Down
20 changes: 20 additions & 0 deletions src/esp/sensor/sensorManagers/SensorManager.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
// Copyright (c) Meta Platforms, Inc. and its affiliates.
// This source code is licensed under the MIT license found in the
// LICENSE file in the root directory of this source tree.

#include "SensorManager.h"

namespace esp {
namespace sensor {

SensorManager::SensorManager()
: SensorBaseManager<esp::sensor::ManagedSensorBase>::SensorBaseManager(
"Sensor") {
this->copyConstructorMap_["ManagedAudioSensor"] =
&SensorManager::createObjCopyCtorMapEntry<
esp::sensor::ManagedAudioSensor>;

} // SensorManager ctor

} // namespace sensor
} // namespace esp
25 changes: 25 additions & 0 deletions src/esp/sensor/sensorManagers/SensorManager.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright (c) Meta Platforms, Inc. and its affiliates.
// This source code is licensed under the MIT license found in the
// LICENSE file in the root directory of this source tree.

#ifndef ESP_SENSOR_SENSORMANAGER_H_
#define ESP_SENSOR_SENSORMANAGER_H_

#include "SensorBaseManager.h"
#include "esp/sensor/sensorWrappers/ManagedAudioSensor.h"
#include "esp/sensor/sensorWrappers/ManagedSensorBase.h"

namespace esp {
namespace sensor {

class SensorManager : public SensorBaseManager<esp::sensor::ManagedSensorBase> {
public:
explicit SensorManager();

public:
ESP_SMART_POINTERS(SensorManager)
}; // class SensorManager

} // namespace sensor
} // namespace esp
#endif // ESP_SENSOR_SENSORMANAGER_H_
57 changes: 57 additions & 0 deletions src/esp/sensor/sensorWrappers/ManagedAudioSensor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
// Copyright (c) Meta Platforms, Inc. and its affiliates.
// This source code is licensed under the MIT license found in the
// LICENSE file in the root directory of this source tree.

#ifndef ESP_SENSOR_MANAGEDAUDIOSENSOR_H_
#define ESP_SENSOR_MANAGEDAUDIOSENSOR_H_

#include <Corrade/Utility/FormatStl.h>
#include <Corrade/Utility/Macros.h>

#include "esp/sensor/AudioSensor.h"
#include "esp/sensor/sensorWrappers/ManagedSensorTemplates.h"

namespace Cr = Corrade;
namespace Mn = Magnum;
namespace esp {
namespace sensor {

/**
* @brief Class for wrapper for sensor objects of all kinds to
* enable Managed Container access.
*/
class ManagedAudioSensor
: public esp::sensor::AbstractManagedSensor<AudioSensor> {
public:
explicit ManagedAudioSensor()
: AbstractManagedSensor<AudioSensor>::AbstractManagedSensor(
"ManagedAudioSensor") {}

// TODO Add appropriate audio sensor getters/setters here

protected:
/**
* @brief Retrieve a comma-separated string holding the header values for
* the info returned for this managed object, type-specific.
*/

std::string getSensorObjInfoHeaderInternal() const override {
return "Output Directory";
}
/**
* @brief Specialization-specific extension of getObjectInfo, comma
* separated info ideal for saving to csv
*/
std::string getSensorObjInfoInternal(
CORRADE_UNUSED std::shared_ptr<AudioSensor>& sp) const override {
// TODO provide info stream for sensors
return "";
}

public:
ESP_SMART_POINTERS(ManagedAudioSensor)
}; // class ManagedAudioSensor
} // namespace sensor
} // namespace esp

#endif // ESP_SENSOR_MANAGEDAUDIOSENSOR_H_
90 changes: 46 additions & 44 deletions src/esp/sensor/sensorWrappers/ManagedSensorBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,89 +5,90 @@
#ifndef ESP_SENSOR_MANAGEDSENSORBASE_H_
#define ESP_SENSOR_MANAGEDSENSORBASE_H_

#include <Corrade/Containers/StringStl.h>
#include <Corrade/Utility/FormatStl.h>
#include <Corrade/Utility/Macros.h>

#include "esp/core/managedContainers/AbstractManagedObject.h"
#include "esp/sensor/Sensor.h"
#include "esp/sensor/VisualSensor.h"

namespace Cr = Corrade;
namespace Mn = Magnum;
namespace esp {
namespace sensor {

/**
* @brief Base class template for wrapper for sensor objects of all kinds to
* enable Managed Container access.
* @brief Base class for wrappers of sensor objects of all kinds to enable
* Managed Container access.
*/
template <class T>
class AbstractManagedSensor
class ManagedSensorBase
: public esp::core::managedContainers::AbstractManagedObject {
public:
static_assert(std::is_base_of<esp::sensor::Sensor, T>::value,
"AbstractManagedSensor :: Managed sensor object type must be "
"derived from esp::sensor::Sensor");

typedef std::weak_ptr<T> WeakObjRef;

explicit AbstractManagedSensor(const std::string& classKey) {
AbstractManagedSensor::setClassKey(classKey);
explicit ManagedSensorBase(const std::string& classKey) {
ManagedSensorBase::setClassKey(classKey);
}

void setObjectRef(const std::shared_ptr<T>& objRef) { weakObjRef_ = objRef; }

~AbstractManagedSensor() override = default;
~ManagedSensorBase() override = default;
/**
* @brief Get the instancing class of the ManagedSensorBase instance. Should
* only be set from implementer's constructor. Used as key in constructor
* function pointer maps in @ref
* esp::core::managedContainers::ManagedContainer.
*/
std::string getClassKey() const override { return classKey_; }

/**
* @brief Retrieve a comma-separated string holding the header values for the
* info returned for this managed object.
* @brief Managed Sensor objects manage their own handles, so this is
* currently unsettable.
*/
std::string getObjectInfoHeader() const override {
return "Type," + getSensorObjInfoHeaderInternal();
}
void setHandle(CORRADE_UNUSED const std::string& name) override {}

/**
* @brief Retrieve a comma-separated informational string about the contents
* of this managed object.
* @brief Retrieve this Managed Sensor object's unique handle.
*/
std::string getObjectInfo() const override {
if (auto sp = this->getObjectReference()) {
namespace CrUt = Cr::Utility;
return Cr::Utility::formatString("{},{},", classKey_,
getSensorObjInfoInternal(sp));
std::string getHandle() const override {
if (auto sp = getObjectReferenceInternal<Sensor>()) {
return sp->getSensorHandle();
}
return Cr::Utility::formatString("Unknown classkey {},", classKey_);
return "";
}

protected:
/**
* @brief Retrieve a comma-separated string holding the header values for
* the info returned for this managed object, type-specific.
* @brief Managed Sensor objects manage their own IDs, so this is
* unsettable.
*/
void setID(CORRADE_UNUSED int ID) override {}

virtual std::string getSensorObjInfoHeaderInternal() const = 0;
/**
* @brief Specialization-specific extension of getObjectInfo, comma
* separated info ideal for saving to csv
* @brief Retrieve this object's unique ID.
*/
virtual std::string getSensorObjInfoInternal(
std::shared_ptr<T>& sp) const = 0;
int getID() const override {
if (auto sp = getObjectReferenceInternal<Sensor>()) {
return sp->getSensorID();
}
return ID_UNDEFINED;
} // getID()

protected:
void setObjectRefInternal(const std::shared_ptr<void>& objRef) {
weakObjRef_ = objRef;
}

/**
* @brief This function accesses the underlying shared pointer of this
* object's @p weakObjRef_ if it exists; if not, it provides a message.
* @return Either a shared pointer of this wrapper's object, or nullptr if
* DNE.
*/
std::shared_ptr<T> inline getObjectReference() const {
std::shared_ptr<T> sp = weakObjRef_.lock();
template <class T>
std::shared_ptr<T> inline getObjectReferenceInternal() const {
std::shared_ptr<void> sp = weakObjRef_.lock();
if (!sp) {
// TODO: Verify object is removed from manager here?
ESP_ERROR()
<< "This sensor object no longer exists. Please delete any variable "
<< "This sensor object no longer exists. Please delete any variable "
"references.";
}
return sp;
return std::static_pointer_cast<T>(sp);
} // getObjectReference

/**
Expand All @@ -105,16 +106,17 @@ class AbstractManagedSensor
* @brief Weak ref to object. If user has copy of this wrapper but object
* has been deleted, this will be nullptr.
*/
WeakObjRef weakObjRef_{};
std::weak_ptr<void> weakObjRef_{};

/**
* @brief Name of instancing class responsible for this managed object
*/
std::string classKey_;

public:
ESP_SMART_POINTERS(AbstractManagedSensor<T>)
ESP_SMART_POINTERS(ManagedSensorBase)
}; // class AbstractManagedSensor

} // namespace sensor
} // namespace esp

Expand Down
Loading

0 comments on commit de8a096

Please sign in to comment.