in src/esp/bindings/SimBindings.cpp [27:320]
void initSimBindings(py::module& m) {
// ==== SimulatorConfiguration ====
py::class_<SimulatorConfiguration, SimulatorConfiguration::ptr>(
m, "SimulatorConfiguration")
.def(py::init(&SimulatorConfiguration::create<>))
.def_readwrite(
"scene_dataset_config_file",
&SimulatorConfiguration::sceneDatasetConfigFile,
R"(The location of the scene dataset configuration file that describes the
dataset to be used.)")
.def_readwrite(
"scene_id", &SimulatorConfiguration::activeSceneName,
R"(Either the name of a stage asset or configuration file, or else the name of a scene
instance configuration, used to initialize the simulator world.)")
.def_readwrite("random_seed", &SimulatorConfiguration::randomSeed)
.def_readwrite("default_agent_id",
&SimulatorConfiguration::defaultAgentId)
.def_readwrite("default_camera_uuid",
&SimulatorConfiguration::defaultCameraUuid)
.def_readwrite("gpu_device_id", &SimulatorConfiguration::gpuDeviceId)
.def_readwrite("allow_sliding", &SimulatorConfiguration::allowSliding)
.def_readwrite("create_renderer", &SimulatorConfiguration::createRenderer)
.def_readwrite(
"leave_context_with_background_renderer",
&SimulatorConfiguration::leaveContextWithBackgroundRenderer,
R"(See tutorials/async_rendering.py)")
.def_readwrite("frustum_culling", &SimulatorConfiguration::frustumCulling)
.def_readwrite("enable_physics", &SimulatorConfiguration::enablePhysics)
.def_readwrite(
"enable_gfx_replay_save",
&SimulatorConfiguration::enableGfxReplaySave,
R"(Enable replay recording. See sim.gfx_replay.save_keyframe.)")
.def_readwrite("physics_config_file",
&SimulatorConfiguration::physicsConfigFile)
.def_readwrite(
"override_scene_light_defaults",
&SimulatorConfiguration::overrideSceneLightDefaults,
R"(Override scene lighting setup to use with value specified below.)")
.def_readwrite("scene_light_setup",
&SimulatorConfiguration::sceneLightSetupKey)
.def_readwrite("load_semantic_mesh",
&SimulatorConfiguration::loadSemanticMesh)
.def_readwrite(
"force_separate_semantic_scene_graph",
&SimulatorConfiguration::forceSeparateSemanticSceneGraph,
R"(Required to support playback of any gfx replay that includes a
stage with a semantic mesh. Set to false otherwise.)")
.def_readwrite("requires_textures",
&SimulatorConfiguration::requiresTextures)
.def(py::self == py::self)
.def(py::self != py::self);
// ==== Simulator ====
py::class_<Simulator, Simulator::ptr>(m, "Simulator")
// modify constructor to pass MetadataMediator
.def(py::init<const SimulatorConfiguration&,
esp::metadata::MetadataMediator::ptr>())
.def("get_active_scene_graph", &Simulator::getActiveSceneGraph,
R"(PYTHON DOES NOT GET OWNERSHIP)",
py::return_value_policy::reference)
.def("get_active_semantic_scene_graph",
&Simulator::getActiveSemanticSceneGraph,
R"(PYTHON DOES NOT GET OWNERSHIP)",
py::return_value_policy::reference)
.def_property_readonly("semantic_scene", &Simulator::getSemanticScene, R"(
The semantic scene graph
.. note-warning::
Not available for all datasets
)")
.def_property_readonly("renderer", &Simulator::getRenderer)
.def_property_readonly(
"gfx_replay_manager", &Simulator::getGfxReplayManager,
R"(Use gfx_replay_manager for replay recording and playback.)")
.def("seed", &Simulator::seed, "new_seed"_a)
.def("reconfigure", &Simulator::reconfigure, "configuration"_a)
.def("reset", &Simulator::reset)
.def(
"close", &Simulator::close, "destroy"_a = true,
R"(Free all loaded assets and GPU contexts. Use destroy=true except where noted in tutorials/async_rendering.py.)")
.def("debug_draw", &Simulator::physicsDebugDraw, "projMat"_a)
.def_property("pathfinder", &Simulator::getPathFinder,
&Simulator::setPathFinder)
.def_property(
"navmesh_visualization", &Simulator::isNavMeshVisualizationActive,
&Simulator::setNavMeshVisualization,
R"(Enable or disable wireframe visualization of current pathfinder's NavMesh.)")
.def_property_readonly("gpu_device", &Simulator::gpuDevice)
.def_property_readonly("random", &Simulator::random)
.def_property_readonly(
"curr_scene_name", &Simulator::getCurSceneInstanceName,
R"(The simplified, but unique, name of the currently loaded scene.)")
.def_property("frustum_culling", &Simulator::isFrustumCullingEnabled,
&Simulator::setFrustumCullingEnabled,
R"(Enable or disable the frustum culling)")
.def_property(
"active_dataset", &Simulator::getActiveSceneDatasetName,
&Simulator::setActiveSceneDatasetName,
R"(The currently active dataset being used. Will attempt to load
configuration files specified if does not already exist.)")
/* --- Template Manager accessors --- */
// We wish a copy of the metadata mediator smart pointer so that we
// increment its ref counter
.def_property(
"metadata_mediator", &Simulator::getMetadataMediator,
&Simulator::setMetadataMediator, py::return_value_policy::copy,
R"(This construct manages all configuration template managers
and the Scene Dataset Configurations)")
.def("get_asset_template_manager", &Simulator::getAssetAttributesManager,
pybind11::return_value_policy::reference,
R"(Get the current dataset's AssetAttributesManager instance
for configuring primitive asset templates.)")
.def("get_lighting_template_manager",
&Simulator::getLightLayoutAttributesManager,
pybind11::return_value_policy::reference,
R"(Get the current dataset's LightLayoutAttributesManager instance
for configuring light templates and layouts.)")
.def("get_object_template_manager",
&Simulator::getObjectAttributesManager,
pybind11::return_value_policy::reference,
R"(Get the current dataset's ObjectAttributesManager instance
for configuring object templates.)")
.def("get_physics_template_manager",
&Simulator::getPhysicsAttributesManager,
pybind11::return_value_policy::reference,
R"(Get the current PhysicsAttributesManager instance
for configuring PhysicsManager templates.)")
.def("get_stage_template_manager", &Simulator::getStageAttributesManager,
pybind11::return_value_policy::reference,
R"(Get the current dataset's StageAttributesManager instance
for configuring simulation stage templates.)")
.def("get_rigid_object_manager", &Simulator::getRigidObjectManager,
pybind11::return_value_policy::reference,
R"(Get the manager responsible for organizing and accessing all the
currently constructed rigid objects.)")
.def("get_articulated_object_manager",
&Simulator::getArticulatedObjectManager,
pybind11::return_value_policy::reference,
R"(Get the manager responsible for organizing and accessing all the
currently constructed articulated objects.)")
.def(
"get_physics_simulation_library",
&Simulator::getPhysicsSimulationLibrary,
R"(Query the physics library implementation currently configured by this Simulator instance.)")
.def(
"get_stage_initialization_template",
&Simulator::getStageInitializationTemplate, "scene_id"_a = 0,
R"(Get a copy of the StageAttributes template used to instance a scene's stage or None if it does not exist.)")
/* --- Kinematics and dynamics --- */
.def(
"step_world", &Simulator::stepWorld, "dt"_a = 1.0 / 60.0,
R"(Step the physics simulation by a desired timestep (dt). Note that resulting world time after step may not be exactly t+dt. Use get_world_time to query current simulation time.)")
.def("get_world_time", &Simulator::getWorldTime,
R"(Query the current simulation world time.)")
.def("get_gravity", &Simulator::getGravity, "scene_id"_a = 0,
R"(Query the gravity vector for a scene.)")
.def("set_gravity", &Simulator::setGravity, "gravity"_a, "scene_id"_a = 0,
R"(Set the gravity vector for a scene.)")
.def("get_stage_is_collidable", &Simulator::getStageIsCollidable,
R"(Get whether or not the static stage is collidable.)")
.def("set_stage_is_collidable", &Simulator::setStageIsCollidable,
"collidable"_a,
R"(Set whether or not the static stage is collidable.)")
.def(
"contact_test", &Simulator::contactTest, "object_id"_a,
"scene_id"_a = 0,
R"(DEPRECATED AND WILL BE REMOVED IN HABITAT-SIM 2.0. Run collision detection and return a binary indicator of penetration between the specified object and any other collision object. Physics must be enabled.)")
.def(
"get_physics_num_active_contact_points",
&Simulator::getPhysicsNumActiveContactPoints,
R"(The number of contact points that were active during the last step. An object resting on another object will involve several active contact points. Once both objects are asleep, the contact points are inactive. This count is a proxy for complexity/cost of collision-handling in the current scene.)")
.def(
"get_physics_num_active_overlapping_pairs",
&Simulator::getPhysicsNumActiveOverlappingPairs,
R"(The number of active overlapping pairs during the last step. When object bounding boxes overlap and either object is active, additional "narrowphase" collision-detection must be run. This count is a proxy for complexity/cost of collision-handling in the current scene.)")
.def(
"get_physics_step_collision_summary",
&Simulator::getPhysicsStepCollisionSummary,
R"(Get a summary of collision-processing from the last physics step.)")
.def("get_physics_contact_points", &Simulator::getPhysicsContactPoints,
R"(Return a list of ContactPointData "
"objects describing the contacts from the most recent physics substep.)")
.def(
"perform_discrete_collision_detection",
&Simulator::performDiscreteCollisionDetection,
R"(Perform discrete collision detection for the scene. Physics must be enabled. Warning: may break simulation determinism.)")
.def(
"cast_ray", &Simulator::castRay, "ray"_a, "max_distance"_a = 100.0,
"scene_id"_a = 0,
R"(Cast a ray into the collidable scene and return hit results. Physics must be enabled. max_distance in units of ray length.)")
.def("set_object_bb_draw", &Simulator::setObjectBBDraw, "draw_bb"_a,
"object_id"_a, "scene_id"_a = 0,
R"(Enable or disable bounding box visualization for an object.)")
.def(
"recompute_navmesh", &Simulator::recomputeNavMesh, "pathfinder"_a,
"navmesh_settings"_a, "include_static_objects"_a = false,
R"(Recompute the NavMesh for a given PathFinder instance using configured NavMeshSettings. Optionally include all MotionType::STATIC objects in the navigability constraints.)")
#ifdef ESP_BUILD_WITH_VHACD
.def(
"apply_convex_hull_decomposition",
&Simulator::convexHullDecomposition, "filename"_a,
"vhacd_params"_a = assets::ResourceManager::VHACDParameters(),
"render_chd_result"_a = false, "save_chd_to_obj"_a = false,
R"(Decomposite an object into its constituent convex hulls with specified VHACD parameters.)")
#endif
.def(
"add_trajectory_object",
[](Simulator& self, const std::string& name,
const std::vector<Mn::Vector3>& pts, int numSegments, float radius,
const Magnum::Color4& color, bool smooth, int numInterps) {
return self.addTrajectoryObject(
name, pts, {Mn::Color3(color.rgb())}, numSegments, radius,
smooth, numInterps);
},
"traj_vis_name"_a, "points"_a, "num_segments"_a = 3,
"radius"_a = .001, "color"_a = Mn::Color4{0.9, 0.1, 0.1, 1.0},
"smooth"_a = false, "num_interpolations"_a = 10,
R"(Build a tube visualization around the passed trajectory of points.
points : (list of 3-tuples of floats) key point locations to use to create trajectory tube.
num_segments : (Integer) the number of segments around the tube to be used to make the visualization.
radius : (Float) the radius of the resultant tube.
color : (4-tuple of float) the color of the trajectory tube.
smooth : (Bool) whether or not to smooth trajectory using a Catmull-Rom spline interpolating spline.
num_interpolations : (Integer) the number of interpolation points to find between successive key points.)")
.def("add_gradient_trajectory_object",
static_cast<int (Simulator::*)(
const std::string&, const std::vector<Mn::Vector3>&,
const std::vector<Mn::Color3>&, int, float, bool, int)>(
&Simulator::addTrajectoryObject),
"traj_vis_name"_a, "points"_a, "colors"_a, "num_segments"_a = 3,
"radius"_a = .001, "smooth"_a = false, "num_interpolations"_a = 10,
R"(Build a tube visualization around the passed trajectory of
points, using the passed colors to build a gradient along the length of the tube.
points : (list of 3-tuples of floats) key point locations to
use to create trajectory tube. num_segments : (Integer) the
number of segments around the tube to be used to make the
visualization. radius : (Float) the radius of the resultant
tube. colors : (List of 3-tuple of byte) the colors to build
the gradient along the length of the trajectory tube. smooth :
(Bool) whether or not to smooth trajectory using a Catmull-Rom
spline interpolating spline. num_interpolations : (Integer) the
number of interpolation points to find between successive key
points.)")
.def(
"save_current_scene_config",
static_cast<bool (Simulator::*)(const std::string&, int) const>(
&Simulator::saveCurrentSceneInstance),
R"(Save the current simulation world's state as a Scene Instance Config JSON
using the passed name. This can be used to reload the stage, objects, articulated
objects and other values as they currently are.)",
"file_name"_a, "scene_id"_a = 0)
.def(
"save_current_scene_config",
static_cast<bool (Simulator::*)(bool, int) const>(
&Simulator::saveCurrentSceneInstance),
R"(Save the current simulation world's state as a Scene Instance Config JSON
using the name of the loaded scene, either overwritten, if overwrite is True, or
with an incrementer in the file name of the form (copy xxxx) where xxxx is a number.
This can be used to reload the stage, objects, articulated
objects and other values as they currently are.)",
"overwrite"_a = false, "scene_id"_a = 0)
.def("get_light_setup", &Simulator::getLightSetup,
"key"_a = DEFAULT_LIGHTING_KEY,
R"(Get a copy of the LightSetup registered with a specific key.)")
.def("get_current_light_setup", &Simulator::getCurrentLightSetup,
R"(Get a copy of the LightSetup used to create the current scene.)")
.def(
"set_light_setup", &Simulator::setLightSetup, "light_setup"_a,
"key"_a = DEFAULT_LIGHTING_KEY,
R"(Register a LightSetup with a specific key. If a LightSetup is already registered with
this key, it will be overridden. All Drawables referencing the key will use the newly
registered LightSetup.)")
/* --- P2P/Fixed Constraints API --- */
.def(
"create_rigid_constraint", &Simulator::createRigidConstraint,
"settings"_a,
R"(Create a rigid constraint between two objects or an object and the world from a RigidConstraintsSettings.)")
.def("update_rigid_constraint", &Simulator::updateRigidConstraint,
"constraint_id"_a, "settings"_a,
R"(Update the settings of a rigid constraint.)")
.def("get_rigid_constraint_settings",
&Simulator::getRigidConstraintSettings, "constraint_id"_a,
R"(Get a copy of the settings for an existing rigid constraint.)")
.def("remove_rigid_constraint", &Simulator::removeRigidConstraint,
"constraint_id"_a, R"(Remove a rigid constraint by id.)")
.def("get_debug_line_render", &Simulator::getDebugLineRender,
pybind11::return_value_policy::reference,
R"(Get visualization helper for rendering lines.)");
}