Skip to content

Commit

Permalink
--Define constant and bindings for stage ID (#2325)
Browse files Browse the repository at this point in the history
* --fix bindings error (!!!)
Improperly terminated string caused a binding to be subsumed into a descriptor string.
* --provide a constant ref to the id used for the rigid stage.
* --add bindings and update tests
* --c++ test that references stage ID
  • Loading branch information
jturner65 authored Feb 26, 2024
1 parent 922fb41 commit d513cc4
Show file tree
Hide file tree
Showing 10 changed files with 28 additions and 23 deletions.
2 changes: 1 addition & 1 deletion examples/viewer.py
Original file line number Diff line number Diff line change
Expand Up @@ -723,7 +723,7 @@ def mouse_press_event(self, event: Application.MouseEvent) -> None:
hit_object, ao_link = -1, -1
hit_info = raycast_results.hits[0]

if hit_info.object_id >= 0:
if hit_info.object_id > habitat_sim.stage_id:
# we hit an non-staged collision object
ro_mngr = self.sim.get_rigid_object_manager()
ao_mngr = self.sim.get_articulated_object_manager()
Expand Down
2 changes: 2 additions & 0 deletions src/esp/bindings/Bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include "esp/assets/ResourceManager.h"
#include "esp/core/Check.h"
#include "esp/core/Configuration.h"
#include "esp/core/Esp.h"
#include "esp/core/RigidState.h"

namespace py = pybind11;
Expand Down Expand Up @@ -44,6 +45,7 @@ PYBIND11_MODULE(habitat_sim_bindings, m) {
#else
false;
#endif
m.attr("stage_id") = esp::RIGID_STAGE_ID;

/* This function pointer is used by ESP_CHECK(). If it's null, it
std::abort()s, if not, it calls it to cause a Python AssertionError */
Expand Down
15 changes: 7 additions & 8 deletions src/esp/bindings/SimBindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,17 +209,16 @@ void initSimBindings(py::module& m) {
&Simulator::getStageInitializationTemplate,
R"(Get a copy of the StageAttributes template used to instance a scene's stage or None if it does not exist.)")

.def("build_semantic_CC_objects", &Simulator::buildSemanticCCObjects,
R"(Get a dictionary of the current semantic scene's connected
components keyed by color or id, where each value is a list of Semantic Objects
corresponding to an individual connected component.")
.def(
"build_semantic_CC_objects", &Simulator::buildSemanticCCObjects,
R"(Get a dictionary of the current semantic scene's connected components keyed by color or id,
where each value is a list of Semantic Objects corresponding to an individual connected component.)")
.def(
"build_vertex_color_map_report",
&Simulator::buildVertexColorMapReport,
R"(Get a list of strings describing first each color found on vertices in the
semantic mesh that is not present in the loaded semantic scene descriptor file,
and then a list of each semantic object whose specified color is not found on
any vertex in the mesh.)")
R"(Get a list of strings describing first each color found on vertices in the semantic mesh that is
not present in the loaded semantic scene descriptor file, and then a list of each semantic object
whose specified color is not found on any vertex in the mesh.)")

/* --- Kinematics and dynamics --- */
.def(
Expand Down
4 changes: 2 additions & 2 deletions src/esp/core/Esp.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ inline std::shared_ptr<Derived> shared_from(Derived* derived) {
/** @brief Returned on failed creation or lookup of an ID. */
constexpr int ID_UNDEFINED = -1;

/** @brief Undefined or invalid attribute in physics property query. */
constexpr double PHYSICS_ATTR_UNDEFINED = -1.0;
/** @brief Object ID of the rigid stage.*/
constexpr int RIGID_STAGE_ID = -1;

static const double NO_TIME = 0.0;

Expand Down
2 changes: 1 addition & 1 deletion src/esp/physics/RigidStage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ namespace physics {

RigidStage::RigidStage(scene::SceneNode* rigidBodyNode,
const assets::ResourceManager& resMgr)
: RigidBase(rigidBodyNode, ID_UNDEFINED, resMgr) {}
: RigidBase(rigidBodyNode, RIGID_STAGE_ID, resMgr) {}

bool RigidStage::initialize(
metadata::attributes::AbstractObjectAttributes::ptr initAttributes) {
Expand Down
13 changes: 7 additions & 6 deletions src/tests/PhysicsTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -724,9 +724,10 @@ void PhysicsTest::testNumActiveContactPoints() {
CORRADE_COMPARE(physicsManager_->getNumActiveContactPoints(), 4);
// simple_room.glb has multiple subparts and our box is near two of them
CORRADE_COMPARE(physicsManager_->getNumActiveOverlappingPairs(), 2);
CORRADE_COMPARE(
physicsManager_->getStepCollisionSummary(),
"[RigidObject, cubeSolid, id 0] vs [Stage, subpart 6], 4 points\n");
const std::string test_string = Cr::Utility::formatString(
"[RigidObject, cubeSolid, id {}] vs [Stage, subpart 6], 4 points\n",
(esp::RIGID_STAGE_ID + 1));
CORRADE_COMPARE(physicsManager_->getStepCollisionSummary(), test_string);

float totalNormalForce = 0;
for (auto& cp : allContactPoints) {
Expand All @@ -736,9 +737,9 @@ void PhysicsTest::testNumActiveContactPoints() {
CORRADE_COMPARE_AS(
(cp.contactNormalOnBInWS - Magnum::Vector3{0.0, 1.0, 0.0}).length(),
1.0e-4, Cr::TestSuite::Compare::LessOrEqual);
// one object is the cube (0), other is the stage (-1)
CORRADE_COMPARE(cp.objectIdA, 0);
CORRADE_COMPARE(cp.objectIdB, -1);
// one object is the cube (id esp::RIGID_STAGE_ID + 1), other is the stage
CORRADE_COMPARE(cp.objectIdA, (esp::RIGID_STAGE_ID + 1));
CORRADE_COMPARE(cp.objectIdB, esp::RIGID_STAGE_ID);
// accumulate the normal force
totalNormalForce += cp.normalForce;
// solver should keep the cube at the contact boundary (~0 penetration)
Expand Down
1 change: 1 addition & 0 deletions src_python/habitat_sim/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@
audio_enabled,
built_with_bullet,
cuda_enabled,
stage_id,
)
from habitat_sim.nav import ( # noqa: F401
GreedyFollowerCodes,
Expand Down
1 change: 1 addition & 0 deletions src_python/habitat_sim/bindings/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,4 +49,5 @@
audio_enabled,
built_with_bullet,
cuda_enabled,
stage_id,
)
9 changes: 5 additions & 4 deletions tests/test_physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -543,7 +543,8 @@ def test_raycast():
atol=0.07,
)
assert abs(raycast_results.hits[0].ray_distance - 6.831) < 0.001
assert raycast_results.hits[0].object_id == -1
# hit stage
assert raycast_results.hits[0].object_id == habitat_sim.stage_id

# add a primitive object to the world and test a ray away from the origin
cube_prim_handle = obj_template_mgr.get_template_handles("cube")[0]
Expand Down Expand Up @@ -906,7 +907,7 @@ def test_articulated_object_add_remove():
robot = art_obj_mgr.add_articulated_object_from_urdf(filepath=robot_file)
assert robot
assert robot.is_alive
assert robot.object_id == 0 # first robot added
assert robot.object_id == habitat_sim.stage_id + 1 # first robot added

# add a second robot
robot2 = art_obj_mgr.add_articulated_object_from_urdf(
Expand Down Expand Up @@ -1859,7 +1860,7 @@ def test_rigid_constraints():
assert robot.translation[1] < -3

# hang AO from the world with P2P
constraint_settings_2.object_id_b = -1
constraint_settings_2.object_id_b = habitat_sim.stage_id
constraint_settings_2.constraint_type = (
habitat_sim.physics.RigidConstraintType.PointToPoint
)
Expand Down Expand Up @@ -1903,7 +1904,7 @@ def test_rigid_constraints():
assert abs(float(angle_error)) < 0.2

# hang the object from its base link
constraint_settings_2.link_id_a = -1
constraint_settings_2.link_id_a = habitat_sim.stage_id
sim.remove_rigid_constraint(constraint_id_2)
constraint_id_2 = sim.create_rigid_constraint(constraint_settings_2)
observations += simulate(sim, 5.0, produce_debug_video)
Expand Down
2 changes: 1 addition & 1 deletion tests/test_simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,7 @@ def test_object_template_editing():

# test adding a new object
obj = rigid_obj_mgr.add_object_by_template_id(template_ids[0])
assert obj.object_id != -1
assert obj.object_id != habitat_sim.stage_id

# test getting initialization templates
stage_init_template = sim.get_stage_initialization_template()
Expand Down

0 comments on commit d513cc4

Please sign in to comment.