From 83b30c2bfe8031977b536ef38851642e243f9bc6 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Thu, 7 Nov 2024 14:56:51 +0800 Subject: [PATCH 1/4] Adds an initial StableBaselines3 RL environment as an example A lot of things are not working. Particularly when `ResetAll` is called, the EnableVelocityChecks does not trigger the phyics system to populate the velocity components. This is a blocker for the current example. Signed-off-by: Arjo Chakravarty --- .../simple_cart_pole/README.md | 37 ++ .../simple_cart_pole/cart_pole.sdf | 368 ++++++++++++++++++ .../simple_cart_pole/cart_pole_env.py | 120 ++++++ 3 files changed, 525 insertions(+) create mode 100644 examples/scripts/reinforcement_learning/simple_cart_pole/README.md create mode 100644 examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf create mode 100644 examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/README.md b/examples/scripts/reinforcement_learning/simple_cart_pole/README.md new file mode 100644 index 0000000000..3bb276b1d4 --- /dev/null +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/README.md @@ -0,0 +1,37 @@ +# Example for Reinforcement Learning (RL) With Gazebo + +This demo world shows you an example of how you can use SDFormat, Ray-RLLIB and Gazebo to perform RL with python. +We start with a very simple cart-pole world. This world is defined in our sdf file `cart_pole.sdf`. It is analogous to +the + +## Create a VENV + +First create a virtual environment using python, +``` +python3 -m venv venv +``` +Lets activate it and install rayrllib and pytorch. +``` +. venv/bin/activate +``` + +Lets install our dependencies +``` +pip install "ray[rllib]" torch +``` + +In the same terminal you should add your gazebo python install directory to the `PYTHONPATH` +If you built gazebo from source in the current working directory this would be: +``` +export PYTHONPATH=$PYTHONPATH:install/lib/python +``` + +You will also need to set PROTOCOL_BUFFERS_PYTHON_IMPLEMENTATION to python due to version +mis-matches. +``` +export PROTOCOL_BUFFERS_PYTHON_IMPLEMENTATION=python +``` + +## Exploring the environment + +You can see the environment by using `gz sim cart_pole.sdf`. \ No newline at end of file diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf new file mode 100644 index 0000000000..6c1a1cd0de --- /dev/null +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf @@ -0,0 +1,368 @@ + + + + + + + 0.001 + 1.0 + + + + + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.325 0 -0 0 + + + -0.151427 -0 1.5 0 -0 0 + + 0.1 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 0.2 0.2 1.5 + + + + 0.5 1.0 0.5 1 + 0.5 1.0 0.5 1 + 0.0 1.0 0.0 1 + + + + + + 0.2 0.2 1.5 + + + + + + + -0.151427 0 2.2 0 -0 0 + + 10.0 + + 1.26164 + 0 + 0 + 4.16519 + 0 + 4.81014 + + + + + + 0.3 0.3 0.3 + + + + 0.5 1.0 0.5 1 + 0.5 1.0 0.5 1 + 0.0 1.0 0.0 1 + + + + + + 0.3 0.3 0.3 + + + + + + + -0.151427 -0 0.175 0 -0 0 + + 1.14395 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 2.01142 1 0.568726 + + + + 0.5 1.0 0.5 1 + 0.5 1.0 0.5 1 + 0.0 1.0 0.0 1 + + + + + + 2.01142 1 0.568726 + + + + + + + 0.554283 0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + 1 + 1 + 0.035 + 0 + 0 0 1 + + + 1 + 1 + 0.1 + + + + + + + + 0.554282 -0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + 1 + 1 + 0.035 + 0 + 0 0 1 + + + 1 + 1 + 0.1 + + + + + + + + -0.957138 -0 -0.125 0 -0 0 + + 1 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + + 0.2 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.2 + + + + + + + chassis + left_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + right_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + caster + + + + 0 0 -0.75 0 0 0 + chassis + pole + + 0 1 0 + + -1.79769e+308 + 1.79769e+308 + + + + + + pole + pole_mass + + + + + + diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py new file mode 100644 index 0000000000..b45fa9599c --- /dev/null +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py @@ -0,0 +1,120 @@ + +import os +import gymnasium as gym +import numpy as np + +from gz.common6 import set_verbosity +from gz.sim9 import TestFixture, World, world_entity, Model, Link +from gz.math8 import Vector3d +from gz.transport14 import Node +from gz.msgs11.world_control_pb2 import WorldControl +from gz.msgs11.world_reset_pb2 import WorldReset +from gz.msgs11.boolean_pb2 import Boolean + +from stable_baselines3 import A2C + +file_path = os.path.dirname(os.path.realpath(__file__)) + +class GzRewardScorer: + def __init__(self): + self.fixture = TestFixture(os.path.join(file_path, 'cart_pole.sdf')) + self.fixture.on_pre_update(self.on_pre_update) + self.fixture.on_post_update(self.on_post_update) + #self.fixture.on_configure(self.on_configure) + self.command = None + self.first_time = True # Hack cause configure does not work well + self.fixture.finalize() + self.server = self.fixture.server() + self.terminated = False + + def on_pre_update(self, info, ecm): + if self.first_time: + print("Enabling checks") + world = World(world_entity(ecm)) + self.model = Model(world.model_by_name(ecm, "vehicle_green")) + self.pole_entity = self.model.link_by_name(ecm, "pole") + self.chassis_entity = self.model.link_by_name(ecm, "chassis") + self.pole = Link(self.pole_entity) + self.pole.enable_velocity_checks(ecm) + self.chassis = Link(self.chassis_entity) + self.chassis.enable_velocity_checks(ecm) + self.first_time = False + if self.command == 1: + self.chassis.add_world_force(Vector3d(0, 100, 0)) + elif self.command == 0: + self.chassis.add_world_force(Vector3d(0, -100, 0)) + + def on_post_update(self, info, ecm): + pole_pose = self.pole.world_pose(ecm).rot().euler().y() + if self.pole.world_angular_velocity(ecm) is not None: + pole_angular_vel = self.pole.world_angular_velocity(ecm).y() + else: + pole_angular_vel = 0 + print("Warning failed to get angular velocity") + cart_pose = self.chassis.world_pose(ecm).pos().x() + cart_vel = self.chassis.world_linear_velocity(ecm) + + if cart_vel is not None: + cart_vel = cart_vel.x() + else: + cart_vel = 0 + print("Warning failed to get cart velocity") + + #print("pole", pole_pose) + #print("cart", cart_pose) + #print("Pole angvel ", pole_angular_vel) + self.state = np.array([cart_pose, cart_vel, pole_pose, pole_angular_vel], dtype=np.float32) + if not self.terminated: + self.terminated = pole_pose > 0.24 or pole_pose < -0.24 or cart_pose > 4.8 or cart_pose < -4.8 + + if self.terminated: + self.reward = 0.0 + else: + self.reward = 1.0 + + def step(self, action, paused=False): + self.action = action + self.server.run(True, 1, paused) + obs = self.state + reward = self.reward + return obs, reward, self.terminated, False, {} + + def reset(self): + print("Resetting") + self.server.reset_all() + self.first_time = True + self.command = None + self.terminated = False + obs, reward_, term_, tunc_, other_= self.step(None, paused=False) + return obs, {} + + + +class CustomCartPole(gym.Env): + def __init__(self, env_config): + self.env = GzRewardScorer() + #self.server = + self.action_space = gym.spaces.Discrete(2)#self.env.action_space + self.observation_space = gym.spaces.Box( + np.array([-10, float("-inf"), -0.418, -3.4028235e+38]), + np.array([10, float("inf"), 0.418, 3.4028235e+38]), + (4,), np.float32) + + def reset(self, seed=123): + return self.env.reset() + + def step(self, action): + obs, reward, done, truncated, info = self.env.step(action) + return obs, reward, done, truncated, info + + +env = CustomCartPole({}) +model = A2C("MlpPolicy", env, verbose=1) +model.learn(total_timesteps=10_000) + +vec_env = model.get_env() +obs = vec_env.reset() +for i in range(5000): + action, _state = model.predict(obs, deterministic=True) + obs, reward, done, info = vec_env.step(action) + # Nice to have spawn a gz sim client \ No newline at end of file From c3eea00d43be4df88eb9c5f20e13ced7fb159b8c Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Mon, 11 Nov 2024 13:12:25 +0800 Subject: [PATCH 2/4] Fixed readme instructions Signed-off-by: Arjo Chakravarty --- .../simple_cart_pole/README.md | 2 +- .../simple_cart_pole/cart_pole_env.py | 27 +++++++------------ 2 files changed, 10 insertions(+), 19 deletions(-) diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/README.md b/examples/scripts/reinforcement_learning/simple_cart_pole/README.md index 3bb276b1d4..2e8f396809 100644 --- a/examples/scripts/reinforcement_learning/simple_cart_pole/README.md +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/README.md @@ -17,7 +17,7 @@ Lets activate it and install rayrllib and pytorch. Lets install our dependencies ``` -pip install "ray[rllib]" torch +pip install stable-baselines3[extra] ``` In the same terminal you should add your gazebo python install directory to the `PYTHONPATH` diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py index b45fa9599c..d032ae5079 100644 --- a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py @@ -20,25 +20,21 @@ def __init__(self): self.fixture = TestFixture(os.path.join(file_path, 'cart_pole.sdf')) self.fixture.on_pre_update(self.on_pre_update) self.fixture.on_post_update(self.on_post_update) - #self.fixture.on_configure(self.on_configure) self.command = None - self.first_time = True # Hack cause configure does not work well self.fixture.finalize() self.server = self.fixture.server() self.terminated = False def on_pre_update(self, info, ecm): - if self.first_time: - print("Enabling checks") - world = World(world_entity(ecm)) - self.model = Model(world.model_by_name(ecm, "vehicle_green")) - self.pole_entity = self.model.link_by_name(ecm, "pole") - self.chassis_entity = self.model.link_by_name(ecm, "chassis") - self.pole = Link(self.pole_entity) - self.pole.enable_velocity_checks(ecm) - self.chassis = Link(self.chassis_entity) - self.chassis.enable_velocity_checks(ecm) - self.first_time = False + + world = World(world_entity(ecm)) + self.model = Model(world.model_by_name(ecm, "vehicle_green")) + self.pole_entity = self.model.link_by_name(ecm, "pole") + self.chassis_entity = self.model.link_by_name(ecm, "chassis") + self.pole = Link(self.pole_entity) + self.pole.enable_velocity_checks(ecm) + self.chassis = Link(self.chassis_entity) + self.chassis.enable_velocity_checks(ecm) if self.command == 1: self.chassis.add_world_force(Vector3d(0, 100, 0)) elif self.command == 0: @@ -60,9 +56,6 @@ def on_post_update(self, info, ecm): cart_vel = 0 print("Warning failed to get cart velocity") - #print("pole", pole_pose) - #print("cart", cart_pose) - #print("Pole angvel ", pole_angular_vel) self.state = np.array([cart_pose, cart_vel, pole_pose, pole_angular_vel], dtype=np.float32) if not self.terminated: self.terminated = pole_pose > 0.24 or pole_pose < -0.24 or cart_pose > 4.8 or cart_pose < -4.8 @@ -80,9 +73,7 @@ def step(self, action, paused=False): return obs, reward, self.terminated, False, {} def reset(self): - print("Resetting") self.server.reset_all() - self.first_time = True self.command = None self.terminated = False obs, reward_, term_, tunc_, other_= self.step(None, paused=False) From 9a2b742f5d28e074570111083cf9fae4cd0b7805 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Mon, 11 Nov 2024 13:15:25 +0800 Subject: [PATCH 3/4] Style Signed-off-by: Arjo Chakravarty --- .../reinforcement_learning/simple_cart_pole/cart_pole.sdf | 1 + .../reinforcement_learning/simple_cart_pole/cart_pole_env.py | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf index 6c1a1cd0de..97d8c0b844 100644 --- a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole.sdf @@ -366,3 +366,4 @@ + diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py index d032ae5079..f94792d314 100644 --- a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py @@ -108,4 +108,4 @@ def step(self, action): for i in range(5000): action, _state = model.predict(obs, deterministic=True) obs, reward, done, info = vec_env.step(action) - # Nice to have spawn a gz sim client \ No newline at end of file + # Nice to have spawn a gz sim client From da33f11442874b450474bd82d772931423f54284 Mon Sep 17 00:00:00 2001 From: Arjo Chakravarty Date: Mon, 11 Nov 2024 17:30:38 +0800 Subject: [PATCH 4/4] Got the gui working. Time for gradient descent by grad student Signed-off-by: Arjo Chakravarty --- .../simple_cart_pole/README.md | 7 +++ .../simple_cart_pole/cart_pole_env.py | 23 ++++---- python/CMakeLists.txt | 2 + python/src/gz/sim/Gui.cc | 52 +++++++++++++++++++ python/src/gz/sim/Gui.hh | 39 ++++++++++++++ python/src/gz/sim/_gz_sim_pybind11.cc | 2 + 6 files changed, 115 insertions(+), 10 deletions(-) create mode 100644 python/src/gz/sim/Gui.cc create mode 100644 python/src/gz/sim/Gui.hh diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/README.md b/examples/scripts/reinforcement_learning/simple_cart_pole/README.md index 2e8f396809..53b2dae9e1 100644 --- a/examples/scripts/reinforcement_learning/simple_cart_pole/README.md +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/README.md @@ -19,6 +19,12 @@ Lets install our dependencies ``` pip install stable-baselines3[extra] ``` +For visuallization to work you will also need to: +``` +pip uninstall opencv-python +pip install opencv-python-headless +``` +This is because `opencv-python` brings in Qt5 by default. In the same terminal you should add your gazebo python install directory to the `PYTHONPATH` If you built gazebo from source in the current working directory this would be: @@ -32,6 +38,7 @@ mis-matches. export PROTOCOL_BUFFERS_PYTHON_IMPLEMENTATION=python ``` + ## Exploring the environment You can see the environment by using `gz sim cart_pole.sdf`. \ No newline at end of file diff --git a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py index f94792d314..31d336b817 100644 --- a/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py +++ b/examples/scripts/reinforcement_learning/simple_cart_pole/cart_pole_env.py @@ -4,14 +4,15 @@ import numpy as np from gz.common6 import set_verbosity -from gz.sim9 import TestFixture, World, world_entity, Model, Link +from gz.sim9 import TestFixture, World, world_entity, Model, Link, run_gui from gz.math8 import Vector3d from gz.transport14 import Node from gz.msgs11.world_control_pb2 import WorldControl from gz.msgs11.world_reset_pb2 import WorldReset from gz.msgs11.boolean_pb2 import Boolean -from stable_baselines3 import A2C +from stable_baselines3 import PPO +import time file_path = os.path.dirname(os.path.realpath(__file__)) @@ -36,9 +37,9 @@ def on_pre_update(self, info, ecm): self.chassis = Link(self.chassis_entity) self.chassis.enable_velocity_checks(ecm) if self.command == 1: - self.chassis.add_world_force(Vector3d(0, 100, 0)) + self.chassis.add_world_force(ecm, Vector3d(2000, 0, 0)) elif self.command == 0: - self.chassis.add_world_force(Vector3d(0, -100, 0)) + self.chassis.add_world_force(ecm, Vector3d(-2000, 0, 0)) def on_post_update(self, info, ecm): pole_pose = self.pole.world_pose(ecm).rot().euler().y() @@ -58,7 +59,7 @@ def on_post_update(self, info, ecm): self.state = np.array([cart_pose, cart_vel, pole_pose, pole_angular_vel], dtype=np.float32) if not self.terminated: - self.terminated = pole_pose > 0.24 or pole_pose < -0.24 or cart_pose > 4.8 or cart_pose < -4.8 + self.terminated = pole_pose > 0.48 or pole_pose < -0.48 or cart_pose > 4.8 or cart_pose < -4.8 if self.terminated: self.reward = 0.0 @@ -66,8 +67,8 @@ def on_post_update(self, info, ecm): self.reward = 1.0 def step(self, action, paused=False): - self.action = action - self.server.run(True, 1, paused) + self.command = action + self.server.run(True, 5, paused) obs = self.state reward = self.reward return obs, reward, self.terminated, False, {} @@ -100,12 +101,14 @@ def step(self, action): env = CustomCartPole({}) -model = A2C("MlpPolicy", env, verbose=1) -model.learn(total_timesteps=10_000) +model = PPO("MlpPolicy", env, verbose=1) +model.learn(total_timesteps=25_000) vec_env = model.get_env() obs = vec_env.reset() -for i in range(5000): +run_gui() +time.sleep(10) +for i in range(50000): action, _state = model.predict(obs, deterministic=True) obs, reward, done, info = vec_env.step(action) # Nice to have spawn a gz sim client diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 98bbe66650..d5ed701042 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -42,10 +42,12 @@ pybind11_add_module(${BINDINGS_MODULE_NAME} MODULE src/gz/sim/UpdateInfo.cc src/gz/sim/Util.cc src/gz/sim/World.cc + src/gz/sim/Gui.cc ) target_link_libraries(${BINDINGS_MODULE_NAME} PRIVATE ${PROJECT_LIBRARY_TARGET_NAME} + ${PROJECT_LIBRARY_TARGET_NAME}-gui gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} ) diff --git a/python/src/gz/sim/Gui.cc b/python/src/gz/sim/Gui.cc new file mode 100644 index 0000000000..c0a04abd3c --- /dev/null +++ b/python/src/gz/sim/Gui.cc @@ -0,0 +1,52 @@ +/* + * 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. + */ + + +#include + +#include +#include + +#include "Server.hh" + +namespace gz +{ +namespace sim +{ +namespace python +{ +void defineGuiClient(pybind11::module &_module) +{ + + _module.def("run_gui", [](){ + auto pid = fork(); + if (pid == -1) + { + gzerr << "Failed to instantiate new process"; + return; + } + if (pid != 0) + { + return; + } + int zero = 0; + gz::sim::gui::runGui(zero, nullptr, nullptr); + }, + "Run the gui"); +} +} // namespace python +} // namespace sim +} // namespace gz diff --git a/python/src/gz/sim/Gui.hh b/python/src/gz/sim/Gui.hh new file mode 100644 index 0000000000..1856f7b18f --- /dev/null +++ b/python/src/gz/sim/Gui.hh @@ -0,0 +1,39 @@ +/* + * 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. + */ + + +#ifndef GZ_SIM_PYTHON___HH_ +#define GZ_SIM_PYTHON__SERVER_HH_ + +#include + +namespace gz +{ +namespace sim +{ +namespace python +{ +/// Define a pybind11 wrapper for a gz::sim::Server +/** + * \param[in] module a pybind11 module to add the definition to + */ +void +defineGuiClient(pybind11::module &_module); +} // namespace python +} // namespace sim +} // namespace gz + +#endif // GZ_SIM_PYTHON__SERVER_HH_ \ No newline at end of file diff --git a/python/src/gz/sim/_gz_sim_pybind11.cc b/python/src/gz/sim/_gz_sim_pybind11.cc index acf9373dc5..9645cd66bf 100644 --- a/python/src/gz/sim/_gz_sim_pybind11.cc +++ b/python/src/gz/sim/_gz_sim_pybind11.cc @@ -32,6 +32,7 @@ #include "UpdateInfo.hh" #include "Util.hh" #include "World.hh" +#include "Gui.hh" PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { m.doc() = "Gazebo Sim Python Library."; @@ -50,4 +51,5 @@ PYBIND11_MODULE(BINDINGS_MODULE_NAME, m) { gz::sim::python::defineSimUpdateInfo(m); gz::sim::python::defineSimWorld(m); gz::sim::python::defineSimUtil(m); + gz::sim::python::defineGuiClient(m); }