From 30439abcdb160d3dd6816da924588e9433b8eeb9 Mon Sep 17 00:00:00 2001 From: Voldivh Date: Wed, 26 Jul 2023 10:25:25 -0500 Subject: [PATCH] Adds test and fixes documentation Signed-off-by: Voldivh --- python/CMakeLists.txt | 1 + python/src/gz/sim/Model.cc | 12 +++--- python/test/model_TEST.py | 82 ++++++++++++++++++++++++++++++++++++++ python/test/model_test.sdf | 25 ++++++++++++ 4 files changed, 114 insertions(+), 6 deletions(-) create mode 100755 python/test/model_TEST.py create mode 100644 python/test/model_test.sdf diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index d36e0dc4b13..559947a6527 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -87,6 +87,7 @@ endif() if (BUILD_TESTING) set(python_tests + model_TEST testFixture_TEST world_TEST ) diff --git a/python/src/gz/sim/Model.cc b/python/src/gz/sim/Model.cc index 2db5f117e5a..7c17010deb5 100644 --- a/python/src/gz/sim/Model.cc +++ b/python/src/gz/sim/Model.cc @@ -38,7 +38,7 @@ void defineSimModel(py::object module) "Get the entity which this Model is related to.") .def("valid", &gz::sim::Model::Valid, py::arg("ecm"), - "Check whether this model correctly refers to an entity that" + "Check whether this model correctly refers to an entity that " "has a components::Model.") .def("name", &gz::sim::Model::Name, py::arg("ecm"), @@ -55,17 +55,17 @@ void defineSimModel(py::object module) .def("source_file_path", &gz::sim::Model::SourceFilePath, py::arg("ecm"), "Get the source file where this model came from. If empty," - "the model wasn't loaded directly from a file, probably from an SDF" + "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"), - "Get the ID of a joint entity which is an immediate child of" + "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"), - "Get the ID of a link entity which is an immediate child of" + "Get the ID of a link entity which is an immediate child of " "this model.") .def("joints", &gz::sim::Model::Joints, py::arg("ecm"), @@ -78,11 +78,11 @@ void defineSimModel(py::object module) "Get all models which are immediate children of this model.") .def("joint_count", &gz::sim::Model::JointCount, py::arg("ecm"), - "Get the number of joints which are immediate children of this" + "Get the number of joints which are immediate children of this " "model.") .def("link_count", &gz::sim::Model::LinkCount, py::arg("ecm"), - "Get the number of links which are immediate children of this" + "Get the number of links which are immediate children of this " "model.") .def("set_world_pose_cmd", &gz::sim::Model::SetWorldPoseCmd, py::arg("ecm"), diff --git a/python/test/model_TEST.py b/python/test/model_TEST.py new file mode 100755 index 00000000000..a26c64329f2 --- /dev/null +++ b/python/test/model_TEST.py @@ -0,0 +1,82 @@ +#!/usr/bin/env python3 +# Copyright (C) 2023 Open Source Robotics Foundation + +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at + +# http://www.apache.org/licenses/LICENSE-2.0 + +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os +import unittest + +from gz.common import set_verbosity +from gz.sim8 import TestFixture, Model, World, world_entity + +post_iterations = 0 +iterations = 0 +pre_iterations = 0 + +class TestModel(unittest.TestCase): + + def test_model(self): + set_verbosity(4) + + file_path = os.path.dirname(os.path.realpath(__file__)) + fixture = TestFixture(os.path.join(file_path, 'model_test.sdf')) + + def on_post_udpate_cb(_info, _ecm): + global post_iterations + post_iterations += 1 + + def on_pre_udpate_cb(_info, _ecm): + global pre_iterations + pre_iterations += 1 + world_e = world_entity(_ecm) + self.assertEqual(1, world_e) + w = World(world_e) + model = Model(w.model_by_name(_ecm, 'model_test')) + # Entity Test + self.assertEqual(4, model.entity()) + # Valid Test + self.assertTrue(model.valid(_ecm)) + # Name Test + self.assertEqual('model_test', model.name(_ecm)) + # Static Test + self.assertTrue(model.static(_ecm)) + # Self Collide Test + self.assertTrue(model.self_collide(_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.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.assertEqual(2, model.link_count(_ecm)) + + def on_udpate_cb(_info, _ecm): + global iterations + iterations += 1 + + fixture.on_post_update(on_post_udpate_cb) + fixture.on_update(on_udpate_cb) + fixture.on_pre_update(on_pre_udpate_cb) + fixture.finalize() + + server = fixture.server() + server.run(True, 1000, False) + + self.assertEqual(1000, pre_iterations) + self.assertEqual(1000, iterations) + self.assertEqual(1000, post_iterations) + +if __name__ == '__main__': + unittest.main() diff --git a/python/test/model_test.sdf b/python/test/model_test.sdf new file mode 100644 index 00000000000..31c6b3f935e --- /dev/null +++ b/python/test/model_test.sdf @@ -0,0 +1,25 @@ + + + + + 0.2 0.1 0.5 0.1 0.3 0.4 + true + true + true + + + 0 0 0 0 0 0 + + + + 0 0 0 0 0 0 + + + + model_link_test_1 + model_link_test_2 + + + + +