Skip to content

Commit 46f5c8d

Browse files
committed
Adds verbose option to PyBullet connection
Adds a `verbose` parameter to the `PyBulletClient.connect()` and `PyBulletClient.disconnect()` methods, allowing users to control the verbosity of the PyBullet connection. This helps in debugging and avoids potential errors related to stdout redirection. Changes the `PyBulletClient._handle_concavity()` to avoid the `redirect_stdout` context manager to avoid the mysterious `WinError 6: The handle is invalid.` error.
1 parent f1d1273 commit 46f5c8d

2 files changed

Lines changed: 10 additions & 7 deletions

File tree

CHANGELOG.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -178,6 +178,8 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
178178
* Changed `TargetMode` to be an enum instead of string.
179179
* Changed default values for number of planning attempts in MoveIt to 5, and the allowed planning time to 1 second.
180180
* Changed cartesian motion planner of MoveIt to raise an exception (including the partial trajectory) if fraction is below 1.0 (ie. the trajectory is not possible).
181+
* Changed `PyBulletClient.connect()` and `PyBulletClient.disconnect()` to take a `verbose` parameter.
182+
* Changed `PyBulletClient._handle_concavity()` to ignore the `redirect_stdout` context manager to avoid the mysterious `WinError 6: The handle is invalid.` error.
181183

182184
### Removed
183185

src/compas_fab/backends/pybullet/client.py

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,7 @@ def connect(
6767
color: Optional[tuple[float, float, float]] = None,
6868
width: Optional[int] = None,
6969
height: Optional[int] = None,
70+
verbose: bool = False,
7071
):
7172
"""Connect from the PyBullet server.
7273
@@ -96,7 +97,7 @@ def connect(
9697
# Format GUI parameters for launching PyBullet
9798
options = self._compose_options(color, width, height)
9899

99-
with redirect_stdout():
100+
with redirect_stdout(enabled=not verbose):
100101
self.client_id = pybullet.connect(const.CONNECTION_TYPE[self.connection_type], options=options)
101102

102103
if self.client_id < 0:
@@ -130,9 +131,9 @@ def _configure_debug_visualizer(self, shadows: bool = True):
130131
)
131132
pybullet.configureDebugVisualizer(pybullet.COV_ENABLE_SHADOWS, shadows, physicsClientId=self.client_id)
132133

133-
def disconnect(self):
134+
def disconnect(self, verbose: bool = False):
134135
"""Disconnect from the PyBullet server."""
135-
with redirect_stdout():
136+
with redirect_stdout(enabled=not verbose):
136137
return pybullet.disconnect(physicsClientId=self.client_id)
137138

138139
@property
@@ -238,12 +239,12 @@ def robot_cell_state(self) -> RobotCellState:
238239

239240
def __enter__(self):
240241
self._cache_dir = tempfile.TemporaryDirectory(prefix="compas_fab")
241-
self.connect()
242+
self.connect(verbose=self.verbose)
242243
return self
243244

244245
def __exit__(self, *args):
245246
self._cache_dir.cleanup()
246-
self.disconnect()
247+
self.disconnect(verbose=self.verbose)
247248

248249
@property
249250
def unordered_disabled_collisions(self) -> set:
@@ -829,8 +830,8 @@ def _handle_concavity(tmp_obj_path, tmp_dir, concavity, mass, mesh_name=""):
829830
mesh_name += "_"
830831
tmp_vhacd_obj_path = os.path.join(tmp_dir, mesh_name + "vhacd_temp.obj")
831832
tmp_log_path = os.path.join(tmp_dir, mesh_name + "log.txt")
832-
with redirect_stdout():
833-
pybullet.vhacd(tmp_obj_path, tmp_vhacd_obj_path, tmp_log_path)
833+
# with redirect_stdout(enabled=not self.verbose):
834+
pybullet.vhacd(tmp_obj_path, tmp_vhacd_obj_path, tmp_log_path)
834835
return tmp_vhacd_obj_path
835836

836837
def _body_from_obj(

0 commit comments

Comments
 (0)