Skip to content

Commit 424aef5

Browse files
Move remaining Pybullet code to dedicated modules (#1171)
- Using IDE functionality
1 parent 82211be commit 424aef5

4 files changed

Lines changed: 30 additions & 28 deletions

File tree

Lines changed: 3 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -1,38 +1,16 @@
1-
"""Interfaces to PyBullet robots."""
1+
"""Motion Planning in Pybullet."""
22
from __future__ import annotations
33

4-
from typing import TYPE_CHECKING, Collection, Iterator, List, Optional, \
5-
Sequence
4+
from typing import Collection, Iterator, Optional, Sequence
65

76
import numpy as np
87
import pybullet as p
98

109
from predicators.src import utils
10+
from predicators.src.pybullet_helpers.robots import SingleArmPyBulletRobot
1111
from predicators.src.settings import CFG
1212
from predicators.src.structs import JointsState
1313

14-
if TYPE_CHECKING:
15-
from predicators.src.pybullet_helpers.robots import SingleArmPyBulletRobot
16-
17-
########################### Other utility functions ###########################
18-
19-
20-
def get_kinematic_chain(robot: int, end_effector: int,
21-
physics_client_id: int) -> List[int]:
22-
"""Get all of the free joints from robot base to end effector.
23-
24-
Includes the end effector.
25-
"""
26-
kinematic_chain = []
27-
while end_effector > -1:
28-
joint_info = p.getJointInfo(robot,
29-
end_effector,
30-
physicsClientId=physics_client_id)
31-
if joint_info[3] > -1:
32-
kinematic_chain.append(end_effector)
33-
end_effector = joint_info[-1]
34-
return kinematic_chain
35-
3614

3715
def run_motion_planning(
3816
robot: SingleArmPyBulletRobot, initial_state: JointsState,

src/pybullet_helpers/robots/single_arm.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,9 +8,9 @@
88
from gym.spaces import Box
99

1010
from predicators.src import utils
11-
from predicators.src.envs.pybullet_robots import get_kinematic_chain
1211
from predicators.src.pybullet_helpers.inverse_kinematics import \
1312
pybullet_inverse_kinematics
13+
from predicators.src.pybullet_helpers.utils import get_kinematic_chain
1414
from predicators.src.settings import CFG
1515
from predicators.src.structs import Array, JointsState, Pose3D
1616

src/pybullet_helpers/utils.py

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
"""Other Pybullet utility functions."""
2+
from __future__ import annotations
3+
4+
from typing import List
5+
6+
import pybullet as p
7+
8+
9+
def get_kinematic_chain(robot: int, end_effector: int,
10+
physics_client_id: int) -> List[int]:
11+
"""Get all of the free joints from robot base to end effector.
12+
13+
Includes the end effector.
14+
"""
15+
kinematic_chain = []
16+
while end_effector > -1:
17+
joint_info = p.getJointInfo(robot,
18+
end_effector,
19+
physicsClientId=physics_client_id)
20+
if joint_info[3] > -1:
21+
kinematic_chain.append(end_effector)
22+
end_effector = joint_info[-1]
23+
return kinematic_chain

tests/envs/test_pybullet_robots.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,12 +6,13 @@
66

77
from predicators.src import utils
88
from predicators.src.envs.pybullet_env import create_pybullet_block
9-
from predicators.src.envs.pybullet_robots import get_kinematic_chain, \
10-
run_motion_planning
119
from predicators.src.pybullet_helpers.inverse_kinematics import \
1210
pybullet_inverse_kinematics
11+
from predicators.src.pybullet_helpers.motion_planning import \
12+
run_motion_planning
1313
from predicators.src.pybullet_helpers.robots import FetchPyBulletRobot, \
1414
create_single_arm_pybullet_robot
15+
from predicators.src.pybullet_helpers.utils import get_kinematic_chain
1516
from predicators.src.settings import CFG
1617

1718

0 commit comments

Comments
 (0)