From 0a5a648c696101d73e47972800a82db4474df5f2 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 4 Sep 2024 19:02:21 +0200 Subject: [PATCH 1/3] [general] Changed pybullet requirement to pycram_bullet --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 00a4b5156..b97da2b03 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,6 +1,6 @@ -r requirements-setuptools.txt gitpython>=3.1.37 -pybullet~=3.2.5 +pycram_bullet==3.2.7 rospkg~=1.4.0 roslibpy~=1.2.1 # rospy~=1.14.11 From 50828da60e19f27a69138d5de52872ae739a0fc6 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Wed, 4 Sep 2024 19:02:42 +0200 Subject: [PATCH 2/3] [BulletWorld/Costmap] Changed pybullet import to pycram_bullet --- src/pycram/costmaps.py | 2 +- src/pycram/worlds/bullet_world.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/pycram/costmaps.py b/src/pycram/costmaps.py index 43938ffcd..ca0dd71b6 100644 --- a/src/pycram/costmaps.py +++ b/src/pycram/costmaps.py @@ -20,7 +20,7 @@ from .datastructures.world import World from .datastructures.dataclasses import AxisAlignedBoundingBox, BoxVisualShape, Color -import pybullet as p +import pycram_bullet as p @dataclass diff --git a/src/pycram/worlds/bullet_world.py b/src/pycram/worlds/bullet_world.py index 5659d9a23..b3f93cb5a 100755 --- a/src/pycram/worlds/bullet_world.py +++ b/src/pycram/worlds/bullet_world.py @@ -5,7 +5,7 @@ import time import numpy as np -import pybullet as p +import pycram_bullet as p import rosgraph import rospy from geometry_msgs.msg import Point From 7edce484ac18aaf8e34a8ae5522a21aeec605b46 Mon Sep 17 00:00:00 2001 From: Jonas Dech Date: Thu, 5 Sep 2024 11:08:19 +0200 Subject: [PATCH 3/3] [general] Updated dependency to pycram_bullet==3.2.8 --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index b97da2b03..a9d33dbe9 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,6 +1,6 @@ -r requirements-setuptools.txt gitpython>=3.1.37 -pycram_bullet==3.2.7 +pycram_bullet==3.2.8 rospkg~=1.4.0 roslibpy~=1.2.1 # rospy~=1.14.11