Skip to content

Commit

Permalink
--Separate scene node definition and extension to address circular dep
Browse files Browse the repository at this point in the history
  • Loading branch information
jturner65 committed Jul 18, 2024
1 parent 8de34a9 commit 0423a45
Show file tree
Hide file tree
Showing 4 changed files with 84 additions and 46 deletions.
5 changes: 3 additions & 2 deletions src/esp/bindings/Bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,11 @@ PYBIND11_MODULE(habitat_sim_bindings, m) {
esp::core::config::initConfigBindings(m);
esp::core::initCoreBindings(m);
esp::geo::initGeoBindings(m);
esp::scene::initSceneBindings(m);
auto pySceneNode = esp::scene::createSceneNodeBind(m);
esp::sensor::initSensorBindings(m);
esp::gfx::initGfxBindings(m);
esp::gfx::replay::initGfxReplayBindings(m);
esp::sensor::initSensorBindings(m);
esp::scene::initSceneBindings(m, pySceneNode);
esp::nav::initShortestPathBindings(m);
esp::sim::initSimConfigBindings(m);
esp::metadata::initAttributesBindings(m);
Expand Down
28 changes: 20 additions & 8 deletions src/esp/bindings/Bindings.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#ifndef ESP_BINDINGS_BINDINGS_H_
#define ESP_BINDINGS_BINDINGS_H_

#include <Magnum/SceneGraph/PythonBindings.h>
#include <pybind11/pybind11.h>
#include "esp/bindings/OpaqueTypes.h"

Expand Down Expand Up @@ -96,6 +97,16 @@ void initPhysicsWrapperManagerBindings(pybind11::module& m);
} // namespace physics

namespace scene {

pybind11::class_<
esp::scene::SceneNode,
Magnum::SceneGraph::PyObject<esp::scene::SceneNode>,
Magnum::SceneGraph::Object<
Magnum::SceneGraph::BasicTranslationRotationScalingTransformation3D<
float>>,
Magnum::SceneGraph::PyObjectHolder<esp::scene::SceneNode>>
createSceneNodeBind(pybind11::module& m);

/**
* @brief Specify bindings for @ref esp::scene::SceneNode , @ref esp::scene::SceneGraph ,
* @ref esp::scene::SceneManager , @ref esp::scene::SemanticCategory ,
Expand All @@ -105,14 +116,15 @@ namespace scene {
* @ref esp::scene::ObjectControls
*/
void initSceneBindings(
pybind11::module& m
// ,
// pybind11::class_<SceneNode,
// Magnum::SceneGraph::PyObject<SceneNode>,
// MagnumObject,
// Magnum::SceneGraph::PyObjectHolder<SceneNode>>&
// pySceneNode
);
pybind11::module& m,
pybind11::class_<
esp::scene::SceneNode,
Magnum::SceneGraph::PyObject<esp::scene::SceneNode>,
Magnum::SceneGraph::Object<
Magnum::SceneGraph::BasicTranslationRotationScalingTransformation3D<
float>>,
Magnum::SceneGraph::PyObjectHolder<esp::scene::SceneNode>>&
pySceneNode);
} // namespace scene

namespace sensor {
Expand Down
85 changes: 55 additions & 30 deletions src/esp/bindings/SceneBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include <Magnum/PythonBindings.h>
#include <Magnum/SceneGraph/PythonBindings.h>

#include "esp/scene/Mp3dSemanticScene.h"
#include "esp/scene/ObjectControls.h"
#include "esp/scene/SceneGraph.h"
Expand All @@ -19,10 +18,61 @@
namespace py = pybind11;
using py::literals::operator""_a;

namespace Mn = Magnum;
namespace esp {
namespace scene {

void initSceneBindings(py::module& m) {
py::class_<esp::scene::SceneNode,
Magnum::SceneGraph::PyObject<esp::scene::SceneNode>,
Magnum::SceneGraph::Object<
Magnum::SceneGraph::
BasicTranslationRotationScalingTransformation3D<float>>,
Magnum::SceneGraph::PyObjectHolder<esp::scene::SceneNode>>
createSceneNodeBind(py::module& m) {
// ==== SceneNode ====
py::class_<esp::scene::SceneNode,
Magnum::SceneGraph::PyObject<esp::scene::SceneNode>,
Magnum::SceneGraph::Object<
Magnum::SceneGraph::
BasicTranslationRotationScalingTransformation3D<float>>,
Magnum::SceneGraph::PyObjectHolder<esp::scene::SceneNode>>
pySceneNode(m, "SceneNode", R"(
SceneNode: a node in the scene graph.
Cannot apply a smart pointer to a SceneNode object.
You can "create it and forget it".
Simulator backend will handle the memory.)");

py::class_<SceneGraph>(m, "SceneGraph")
.def(py::init())
.def("get_root_node",
py::overload_cast<>(&SceneGraph::getRootNode, py::const_),
R"(
Get the root node of the scene graph.
User can specify transformation of the root node w.r.t. the world
frame. (const function) PYTHON DOES NOT GET OWNERSHIP)",
py::return_value_policy::reference)
.def("get_root_node", py::overload_cast<>(&SceneGraph::getRootNode),
R"(
Get the root node of the scene graph.
User can specify transformation of the root node w.r.t. the world
frame. PYTHON DOES NOT GET OWNERSHIP)",
py::return_value_policy::reference);

return pySceneNode;
}

void initSceneBindings(
py::module& m,
py::class_<esp::scene::SceneNode,
Magnum::SceneGraph::PyObject<esp::scene::SceneNode>,
Magnum::SceneGraph::Object<
Magnum::SceneGraph::
BasicTranslationRotationScalingTransformation3D<float>>,
Magnum::SceneGraph::PyObjectHolder<esp::scene::SceneNode>>&
pySceneNode) {
// ==== SceneGraph ====

// !!Warning!!
Expand All @@ -41,14 +91,7 @@ void initSceneBindings(py::module& m) {
.value("CAMERA", SceneNodeType::CAMERA)
.value("OBJECT", SceneNodeType::OBJECT);

// ==== SceneNode ====
py::class_<SceneNode, Magnum::SceneGraph::PyObject<SceneNode>, MagnumObject,
Magnum::SceneGraph::PyObjectHolder<SceneNode>>(m, "SceneNode", R"(
SceneNode: a node in the scene graph.
Cannot apply a smart pointer to a SceneNode object.
You can "create it and forget it".
Simulator backend will handle the memory.)")
pySceneNode
.def(py::init_alias<std::reference_wrapper<SceneNode>>(),
R"(Constructor: creates a scene node, and sets its parent.)")
.def_property("type", &SceneNode::getType, &SceneNode::setType)
Expand Down Expand Up @@ -93,24 +136,6 @@ void initSceneBindings(py::module& m) {
.def_property_readonly("subtree_sensors", &SceneNode::getSubtreeSensors,
R"(Get subtree sensors of this SceneNode)");

py::class_<SceneGraph>(m, "SceneGraph")
.def(py::init())
.def("get_root_node",
py::overload_cast<>(&SceneGraph::getRootNode, py::const_),
R"(
Get the root node of the scene graph.
User can specify transformation of the root node w.r.t. the world
frame. (const function) PYTHON DOES NOT GET OWNERSHIP)",
pybind11::return_value_policy::reference)
.def("get_root_node", py::overload_cast<>(&SceneGraph::getRootNode),
R"(
Get the root node of the scene graph.
User can specify transformation of the root node w.r.t. the world
frame. PYTHON DOES NOT GET OWNERSHIP)",
pybind11::return_value_policy::reference);

// ==== SceneManager ====
py::class_<SceneManager>(m, "SceneManager")
.def("init_scene_graph", &SceneManager::initSceneGraph,
Expand All @@ -122,14 +147,14 @@ void initSceneBindings(py::module& m) {
Get the scene graph by scene graph ID.
PYTHON DOES NOT GET OWNERSHIP)",
"sceneGraphID"_a, pybind11::return_value_policy::reference)
"sceneGraphID"_a, py::return_value_policy::reference)
.def("get_scene_graph",
py::overload_cast<int>(&SceneManager::getSceneGraph, py::const_),
R"(
Get the scene graph by scene graph ID.
PYTHON DOES NOT GET OWNERSHIP)",
"sceneGraphID"_a, pybind11::return_value_policy::reference);
"sceneGraphID"_a, py::return_value_policy::reference);

// ==== SemanticCategory ====
py::class_<SemanticCategory, SemanticCategory::ptr>(m, "SemanticCategory")
Expand Down
12 changes: 6 additions & 6 deletions src/esp/bindings/SensorBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,12 +163,6 @@ void initSensorBindings(py::module& m) {
.def_readwrite("alpha", &FisheyeSensorDoubleSphereSpec::alpha)
.def_readwrite("xi", &FisheyeSensorDoubleSphereSpec::xi);

// ==== SensorFactory ====
py::class_<SensorFactory>(m, "SensorFactory")
.def("create_sensors", &SensorFactory::createSensors)
.def("delete_sensor", &SensorFactory::deleteSensor)
.def("delete_subtree_sensor", &SensorFactory::deleteSubtreeSensor);

// ==== Sensor ====
py::class_<Sensor, Magnum::SceneGraph::PyFeature<Sensor>,
Magnum::SceneGraph::AbstractFeature3D,
Expand Down Expand Up @@ -197,6 +191,12 @@ void initSensorBindings(py::module& m) {
"Node this object is attached to")
.def_property_readonly("object", nodeGetter<Sensor>, "Alias to node");

// ==== SensorFactory ====
py::class_<SensorFactory>(m, "SensorFactory")
.def("create_sensors", &SensorFactory::createSensors)
.def("delete_sensor", &SensorFactory::deleteSensor)
.def("delete_subtree_sensor", &SensorFactory::deleteSubtreeSensor);

// ==== VisualSensor ====
py::class_<VisualSensor, Magnum::SceneGraph::PyFeature<VisualSensor>, Sensor,
Magnum::SceneGraph::PyFeatureHolder<VisualSensor>>(m,
Expand Down

0 comments on commit 0423a45

Please sign in to comment.