Skip to content

Commit

Permalink
Adds bindings for the world convenience class (#2035)
Browse files Browse the repository at this point in the history
Signed-off-by: Voldivh <[email protected]>
  • Loading branch information
Voldivh authored Aug 8, 2023
1 parent 65219b5 commit aef0335
Show file tree
Hide file tree
Showing 9 changed files with 209 additions and 12 deletions.
1 change: 1 addition & 0 deletions .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ python3-distutils
python3-gz-math7
python3-pybind11
python3-pytest
python3-sdformat14
qml-module-qt-labs-folderlistmodel
qml-module-qt-labs-settings
qml-module-qtgraphicaleffects
Expand Down
1 change: 1 addition & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ endif()
if (BUILD_TESTING)
set(python_tests
testFixture_TEST
world_TEST
)

execute_process(COMMAND "${GZ_PYTHON_EXECUTABLE}" -m pytest --version
Expand Down
78 changes: 66 additions & 12 deletions python/src/gz/sim/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,27 +18,81 @@
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>

#include <iostream>

#include "World.hh"

namespace py = pybind11;

namespace gz
{
namespace sim
{
namespace python
{
void defineSimWorld(pybind11::object module)
void defineSimWorld(py::object module)
{
pybind11::class_<gz::sim::World>(module, "World")
.def(pybind11::init<gz::sim::Entity>())
.def(
"model_by_name", &gz::sim::World::ModelByName,
"Get the ID of a model entity which is an immediate child of "
" this world.")
.def(
"gravity", &gz::sim::World::Gravity,
"Get the gravity in m/s^2.");
py::class_<gz::sim::World>(module, "World")
.def(py::init<gz::sim::Entity>())
.def("entity", &gz::sim::World::Entity,
"Get the entity which this World is related to.")
.def("valid", &gz::sim::World::Valid,
py::arg("ecm"),
"Check whether this world correctly refers to an entity that "
"has a components::World.")
.def("name", &gz::sim::World::Name,
py::arg("ecm"),
"Get the world's unscoped name.")
.def("gravity", &gz::sim::World::Gravity,
py::arg("ecm"),
"Get the gravity in m/s^2.")
.def("magnetic_field", &gz::sim::World::MagneticField,
py::arg("ecm"),
"Get the magnetic field in Tesla.")
.def("atmosphere", &gz::sim::World::Atmosphere,
py::arg("ecm"),
"Get atmosphere information.")
.def("spherical_coordinates", &gz::sim::World::SphericalCoordinates,
py::arg("ecm"),
"Get spherical coordinates for the world origin.")
.def("set_spherical_coordinates", &gz::sim::World::SetSphericalCoordinates,
py::arg("ecm"),
py::arg("spherical_coordinates"),
"Set spherical coordinates for the world origin.")
.def("light_by_name", &gz::sim::World::LightByName,
py::arg("ecm"),
py::arg("name"),
"Get the ID of a light entity which is an immediate child of "
"this world.")
.def("actor_by_name", &gz::sim::World::ActorByName,
py::arg("ecm"),
py::arg("name"),
"Get the ID of a actor entity which is an immediate child of "
"this world.")
.def("model_by_name", &gz::sim::World::ModelByName,
py::arg("ecm"),
py::arg("name"),
"Get the ID of a model entity which is an immediate child of "
"this world.")
.def("lights", &gz::sim::World::Lights,
py::arg("ecm"),
"Get all lights which are immediate children of this world.")
.def("actors", &gz::sim::World::Actors,
py::arg("ecm"),
"Get all actors which are immediate children of this world.")
.def("models", &gz::sim::World::Models,
py::arg("ecm"),
"Get all models which are immediate children of this world.")
.def("light_count", &gz::sim::World::LightCount,
py::arg("ecm"),
"Get the number of lights which are immediate children of this "
"world.")
.def("actor_count", &gz::sim::World::ActorCount,
py::arg("ecm"),
"Get the number of actors which are immediate children of this "
"world.")
.def("model_count", &gz::sim::World::ModelCount,
py::arg("ecm"),
"Get the number of models which are immediate children of this "
"world.");
}
} // namespace python
} // namespace sim
Expand Down
Empty file.
1 change: 1 addition & 0 deletions python/test/gz_test_deps/math.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
from gz.math7 import *
1 change: 1 addition & 0 deletions python/test/gz_test_deps/sdformat.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
from sdformat14 import *
1 change: 1 addition & 0 deletions python/test/gz_test_deps/sim.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
from gz.sim8 import *
99 changes: 99 additions & 0 deletions python/test/world_TEST.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
#!/usr/bin/env python3
# Copyright (C) 2021 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_test_deps.sim import TestFixture, World, world_entity
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):

def test_world(self):
set_verbosity(4)

file_path = os.path.dirname(os.path.realpath(__file__))
fixture = TestFixture(os.path.join(file_path, 'world_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)
world = World(world_e)
# Valid Test
self.assertTrue(world.valid(_ecm))
# Name Test
self.assertEqual('world_test', world.name(_ecm))
# Gravity Test
self.assertEqual(Vector3d(0, 0, -10), world.gravity(_ecm))
# Magnetic Field Test
self.assertEqual(Vector3d(1, 2, 3), world.magnetic_field(_ecm))
# Atmosphere Test
atmosphere = world.atmosphere(_ecm)
self.assertEqual(300, atmosphere.temperature())
self.assertEqual(100000, atmosphere.pressure())
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:
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())
self.assertAlmostEqual(float(25), world.spherical_coordinates(_ecm).heading_offset().degree())
world.set_spherical_coordinates(_ecm, SphericalCoordinates())
else:
self.assertAlmostEqual(float(0), world.spherical_coordinates(_ecm).latitude_reference().degree())
self.assertAlmostEqual(float(0), world.spherical_coordinates(_ecm).longitude_reference().degree())
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.assertEqual(1, world.light_count(_ecm))
# Actor test
self.assertEqual(6, 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.assertEqual(1, world.model_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()
39 changes: 39 additions & 0 deletions python/test/world_test.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="world_test">
<physics name="1ms" type="ignored">
<max_step_size>0.01</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<gravity>0 0 -10</gravity>
<magnetic_field>1 2 3</magnetic_field>
<atmosphere type="adiabatic">
<temperature>300</temperature>
<pressure>100000</pressure>
<temperature_gradient>-0.005</temperature_gradient>
</atmosphere>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>10</latitude_deg>
<longitude_deg>15</longitude_deg>
<elevation>20</elevation>
<heading_deg>25</heading_deg>
</spherical_coordinates>

<light type="point" name="light_point_test">
</light>

<actor name="actor_test">
</actor>

<model name="model_test">
<link name="model_link_test">
<pose>0 0 0 0 0 0</pose>
</link>
</model>
</world>
</sdf>

0 comments on commit aef0335

Please sign in to comment.