Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adds bindings for the model convenience class #2036

Merged
merged 24 commits into from
Aug 12, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 12 additions & 1 deletion python/src/gz/sim/Model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,63 +32,74 @@
{
py::class_<gz::sim::Model>(module, "Model")
.def(py::init<gz::sim::Entity>())
azeey marked this conversation as resolved.
Show resolved Hide resolved
.def(py::init<gz::sim::Model>())
.def("entity", &gz::sim::Model::Entity,
"Get the entity which this Model is related to.")
.def("valid", &gz::sim::Model::Valid,
py::arg("ecm"),

Check warning on line 39 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L39

Added line #L39 was not covered by tests
"Check whether this model correctly refers to an entity that "
"has a components::Model.")
.def("name", &gz::sim::Model::Name,
py::arg("ecm"),

Check warning on line 43 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L43

Added line #L43 was not covered by tests
"Get the model's unscoped name.")
.def("static", &gz::sim::Model::Static,
py::arg("ecm"),

Check warning on line 46 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L46

Added line #L46 was not covered by tests
"Get whether this model is static.")
.def("self_collide", &gz::sim::Model::SelfCollide,
py::arg("ecm"),

Check warning on line 49 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L49

Added line #L49 was not covered by tests
"Get whether this model has self-collide enabled.")
.def("wind_mode", &gz::sim::Model::WindMode,
py::arg("ecm"),

Check warning on line 52 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L52

Added line #L52 was not covered by tests
"Get whether this model has wind enabled.")
.def("source_file_path", &gz::sim::Model::SourceFilePath,
py::arg("ecm"),

Check warning on line 55 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L55

Added line #L55 was not covered by tests
"Get the source file where this model came from. If empty,"
"the model wasn't loaded directly from a file, probably from an SDF "
"string.")
.def("joint_by_name", &gz::sim::Model::JointByName,
py::arg("ecm"),
py::arg("name"),

Check warning on line 61 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L60-L61

Added lines #L60 - L61 were not covered by tests
"Get the ID of a joint entity which is an immediate child of "
"this model.")
.def("link_by_name", &gz::sim::Model::LinkByName,
py::arg("ecm"),
py::arg("name"),

Check warning on line 66 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L65-L66

Added lines #L65 - L66 were not covered by tests
"Get the ID of a link entity which is an immediate child of "
"this model.")
.def("joints", &gz::sim::Model::Joints,
py::arg("ecm"),

Check warning on line 70 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L70

Added line #L70 was not covered by tests
"Get all joints which are immediate children of this model.")
.def("links", &gz::sim::Model::Links,
py::arg("ecm"),

Check warning on line 73 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L73

Added line #L73 was not covered by tests
"Get all links which are immediate children of this model.")
.def("models", &gz::sim::Model::Models,
py::arg("ecm"),

Check warning on line 76 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L76

Added line #L76 was not covered by tests
"Get all models which are immediate children of this model.")
.def("joint_count", &gz::sim::Model::JointCount,
py::arg("ecm"),

Check warning on line 79 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L79

Added line #L79 was not covered by tests
"Get the number of joints which are immediate children of this "
"model.")
.def("link_count", &gz::sim::Model::LinkCount,
py::arg("ecm"),

Check warning on line 83 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L83

Added line #L83 was not covered by tests
"Get the number of links which are immediate children of this "
"model.")
.def("set_world_pose_cmd", &gz::sim::Model::SetWorldPoseCmd,
py::arg("ecm"),
py::arg("pose"),

Check warning on line 88 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L87-L88

Added lines #L87 - L88 were not covered by tests
"Set a command to change the model's pose.")
.def("canonical_link", &gz::sim::Model::CanonicalLink,
py::arg("ecm"),

Check warning on line 91 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L91

Added line #L91 was not covered by tests
"Get the model's canonical link entity.");
"Get the model's canonical link entity.")
.def("__copy__",
[](const gz::sim::Model &self)

Check warning on line 94 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L94

Added line #L94 was not covered by tests
{
return gz::sim::Model(self);

Check warning on line 96 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L96

Added line #L96 was not covered by tests
})
.def("__deepcopy__",
[](const gz::sim::Model &self, pybind11::dict)

Check warning on line 99 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L99

Added line #L99 was not covered by tests
{
return gz::sim::Model(self);

Check warning on line 101 in python/src/gz/sim/Model.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/Model.cc#L101

Added line #L101 was not covered by tests
});
}
} // namespace python
} // namespace sim
Expand Down
13 changes: 12 additions & 1 deletion python/src/gz/sim/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
{
py::class_<gz::sim::World>(module, "World")
.def(py::init<gz::sim::Entity>())
.def(py::init<gz::sim::World>())
.def("entity", &gz::sim::World::Entity,
"Get the entity which this World is related to.")
.def("valid", &gz::sim::World::Valid,
Expand Down Expand Up @@ -92,7 +93,17 @@
.def("model_count", &gz::sim::World::ModelCount,
py::arg("ecm"),
"Get the number of models which are immediate children of this "
"world.");
"world.")
.def("__copy__",
[](const gz::sim::World &self)

Check warning on line 98 in python/src/gz/sim/World.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/World.cc#L98

Added line #L98 was not covered by tests
{
return gz::sim::World(self);

Check warning on line 100 in python/src/gz/sim/World.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/World.cc#L100

Added line #L100 was not covered by tests
})
.def("__deepcopy__",
[](const gz::sim::World &self, pybind11::dict)

Check warning on line 103 in python/src/gz/sim/World.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/World.cc#L103

Added line #L103 was not covered by tests
{
return gz::sim::World(self);

Check warning on line 105 in python/src/gz/sim/World.cc

View check run for this annotation

Codecov / codecov/patch

python/src/gz/sim/World.cc#L105

Added line #L105 was not covered by tests
});
}
} // namespace python
} // namespace sim
Expand Down
33 changes: 15 additions & 18 deletions python/test/model_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@
from gz.common import set_verbosity
from gz_test_deps.sim import TestFixture, Model, World, world_entity

post_iterations = 0
iterations = 0
pre_iterations = 0

class TestModel(unittest.TestCase):
k_null_entity = 0
azeey marked this conversation as resolved.
Show resolved Hide resolved
post_iterations = 0
iterations = 0
pre_iterations = 0

def test_model(self):
set_verbosity(4)
Expand All @@ -32,18 +32,16 @@ def test_model(self):
fixture = TestFixture(os.path.join(file_path, 'model_test.sdf'))

def on_post_udpate_cb(_info, _ecm):
global post_iterations
post_iterations += 1
self.post_iterations += 1

def on_pre_udpate_cb(_info, _ecm):
global pre_iterations
pre_iterations += 1
self.pre_iterations += 1
world_e = world_entity(_ecm)
self.assertEqual(1, world_e)
self.assertNotEqual(self.k_null_entity, world_e)
w = World(world_e)
model = Model(w.model_by_name(_ecm, 'model_test'))
# Entity Test
self.assertEqual(4, model.entity())
self.assertNotEqual(self.k_null_entity, model.entity())
# Valid Test
self.assertTrue(model.valid(_ecm))
# Name Test
Expand All @@ -55,16 +53,15 @@ def on_pre_udpate_cb(_info, _ecm):
# Wind Mode Test
self.assertTrue(model.wind_mode(_ecm))
# Get Joints Test
self.assertEqual(7, model.joint_by_name(_ecm, 'model_joint_test'))
self.assertNotEqual(self.k_null_entity, model.joint_by_name(_ecm, 'model_joint_test'))
self.assertEqual(1, model.joint_count(_ecm))
# Get Links Test
self.assertEqual(5, model.link_by_name(_ecm, 'model_link_test_1'))
self.assertEqual(6, model.link_by_name(_ecm, 'model_link_test_2'))
self.assertNotEqual(self.k_null_entity, model.link_by_name(_ecm, 'model_link_test_1'))
self.assertNotEqual(self.k_null_entity, model.link_by_name(_ecm, 'model_link_test_2'))
self.assertEqual(2, model.link_count(_ecm))

def on_udpate_cb(_info, _ecm):
global iterations
iterations += 1
self.iterations += 1

fixture.on_post_update(on_post_udpate_cb)
fixture.on_update(on_udpate_cb)
Expand All @@ -74,9 +71,9 @@ def on_udpate_cb(_info, _ecm):
server = fixture.server()
server.run(True, 1000, False)

self.assertEqual(1000, pre_iterations)
self.assertEqual(1000, iterations)
self.assertEqual(1000, post_iterations)
self.assertEqual(1000, self.pre_iterations)
self.assertEqual(1000, self.iterations)
self.assertEqual(1000, self.post_iterations)

if __name__ == '__main__':
unittest.main()
2 changes: 1 addition & 1 deletion python/test/model_test.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<pose>0 0 0 0 0 0</pose>
</link>

<joint name="model_joint_test" type="revolute">
<joint name="model_joint_test" type="fixed">
<parent>model_link_test_1</parent>
<child>model_link_test_2</child>
azeey marked this conversation as resolved.
Show resolved Hide resolved
</joint>
Expand Down
33 changes: 15 additions & 18 deletions python/test/world_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,11 @@
from gz_test_deps.math import SphericalCoordinates, Vector3d
from gz_test_deps.sdformat import Atmosphere

post_iterations = 0
iterations = 0
pre_iterations = 0

class TestWorld(unittest.TestCase):
k_null_entity = 0
post_iterations = 0
iterations = 0
pre_iterations = 0

def test_world(self):
set_verbosity(4)
Expand All @@ -34,14 +34,12 @@ def test_world(self):
fixture = TestFixture(os.path.join(file_path, 'world_test.sdf'))

def on_post_udpate_cb(_info, _ecm):
global post_iterations
post_iterations += 1
self.post_iterations += 1

def on_pre_udpate_cb(_info, _ecm):
global pre_iterations
pre_iterations += 1
self.pre_iterations += 1
world_e = world_entity(_ecm)
self.assertEqual(1, world_e)
self.assertNotEqual(self.k_null_entity, world_e)
world = World(world_e)
# Valid Test
self.assertTrue(world.valid(_ecm))
Expand All @@ -58,7 +56,7 @@ def on_pre_udpate_cb(_info, _ecm):
self.assertEqual(-0.005, atmosphere.temperature_gradient())
# Spherical Coordinates Test
self.assertEqual(SphericalCoordinates.SurfaceType.EARTH_WGS84, world.spherical_coordinates(_ecm).surface())
if pre_iterations <= 1:
if self.pre_iterations <= 1:
self.assertAlmostEqual(float(10), world.spherical_coordinates(_ecm).latitude_reference().degree())
self.assertAlmostEqual(float(15), world.spherical_coordinates(_ecm).longitude_reference().degree())
self.assertAlmostEqual(float(20), world.spherical_coordinates(_ecm).elevation_reference())
Expand All @@ -70,18 +68,17 @@ def on_pre_udpate_cb(_info, _ecm):
self.assertAlmostEqual(float(0), world.spherical_coordinates(_ecm).elevation_reference())
self.assertAlmostEqual(float(0), world.spherical_coordinates(_ecm).heading_offset().degree())
# Light Test
self.assertEqual(7, world.light_by_name(_ecm, 'light_point_test'))
self.assertNotEqual(self.k_null_entity, world.light_by_name(_ecm, 'light_point_test'))
self.assertEqual(1, world.light_count(_ecm))
# Actor test
self.assertEqual(6, world.actor_by_name(_ecm, 'actor_test'))
self.assertNotEqual(self.k_null_entity, world.actor_by_name(_ecm, 'actor_test'))
self.assertEqual(1, world.actor_count(_ecm))
# Model Test
self.assertEqual(4, world.model_by_name(_ecm, 'model_test'))
self.assertNotEqual(self.k_null_entity, world.model_by_name(_ecm, 'model_test'))
self.assertEqual(1, world.model_count(_ecm))

def on_udpate_cb(_info, _ecm):
global iterations
iterations += 1
self.iterations += 1

fixture.on_post_update(on_post_udpate_cb)
fixture.on_update(on_udpate_cb)
Expand All @@ -91,9 +88,9 @@ def on_udpate_cb(_info, _ecm):
server = fixture.server()
server.run(True, 1000, False)

self.assertEqual(1000, pre_iterations)
self.assertEqual(1000, iterations)
self.assertEqual(1000, post_iterations)
self.assertEqual(1000, self.pre_iterations)
self.assertEqual(1000, self.iterations)
self.assertEqual(1000, self.post_iterations)

if __name__ == '__main__':
unittest.main()