Skip to content

Commit ede5ae9

Browse files
committed
Merge branch 'wip_process' of https://github.com/compas-dev/compas_fab into wip_process
2 parents a75887d + 81a91df commit ede5ae9

11 files changed

Lines changed: 146 additions & 97 deletions

File tree

src/compas_fab/backends/kinematics/backend_features/analytical_inverse_kinematics.py

Lines changed: 24 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,20 @@
1-
from compas import IPY
1+
from typing import TYPE_CHECKING
2+
from typing import Optional
3+
from typing import Generator
4+
5+
from compas.geometry import Frame
6+
from compas_robots import Configuration
27

38
from compas_fab.backends.exceptions import BackendTargetNotSupportedError
49
from compas_fab.backends.exceptions import InverseKinematicsError
510
from compas_fab.backends.interfaces import InverseKinematics
611

7-
if not IPY:
8-
from typing import TYPE_CHECKING
12+
from compas_fab.robots import RobotCell
13+
from compas_fab.robots import RobotCellState
14+
from compas_fab.robots import Target
915

10-
if TYPE_CHECKING: # pragma: no cover
11-
from compas.geometry import Frame # noqa: F401
12-
from compas_fab.backends import AnalyticalKinematicsPlanner # noqa: F401
13-
from compas_robots import Configuration # noqa: F401
14-
from compas_fab.robots import RobotCellState # noqa: F401
15-
from compas_fab.robots import RobotCell # noqa: F401
16-
from compas_fab.robots import Target # noqa: F401
17-
from typing import Dict # noqa: F401
18-
from typing import Optional # noqa: F401
19-
from typing import Generator # noqa: F401
16+
if TYPE_CHECKING:
17+
from compas_fab.backends import AnalyticalKinematicsPlanner
2018

2119
from compas_fab.robots import FrameTarget
2220

@@ -40,8 +38,9 @@ class AnalyticalInverseKinematics(InverseKinematics):
4038
that supports ``"check_collision"``, so for now only the `PyBulletClient`.
4139
"""
4240

43-
def iter_inverse_kinematics(self, target, start_state=None, group=None, options=None):
44-
# type: (Target, Optional[RobotCellState], Optional[str], Optional[Dict]) -> Generator[Configuration | None]
41+
def iter_inverse_kinematics(
42+
self, target: Target, start_state: RobotCellState, group: Optional[str], options: Optional[dict] = None
43+
) -> Generator[Configuration | None, None, None]:
4544
"""Calculate the robot's inverse kinematic for a given target.
4645
4746
An iterator is returned that yields configurations.
@@ -55,8 +54,9 @@ def iter_inverse_kinematics(self, target, start_state=None, group=None, options=
5554
else:
5655
raise BackendTargetNotSupportedError()
5756

58-
def _iter_inverse_kinematics_frame_target(self, target, start_state=None, group=None, options=None):
59-
# type: (FrameTarget, Optional[RobotCellState], Optional[str], Optional[Dict]) -> Generator[Configuration | None]
57+
def _iter_inverse_kinematics_frame_target(
58+
self, target: FrameTarget, start_state: RobotCellState, group: Optional[str], options: Optional[dict] = None
59+
) -> Generator[Configuration | None, None, None]:
6060
"""Calculate the robot's inverse kinematic for a given frame target.
6161
6262
The IK for 6-axis industrial robots returns by default 8 possible solutions.
@@ -74,8 +74,8 @@ def _iter_inverse_kinematics_frame_target(self, target, start_state=None, group=
7474
7575
This function handles the case where the target is a :class:`compas_fab.robots.FrameTarget`.
7676
"""
77-
planner = self # type: AnalyticalKinematicsPlanner
78-
robot_cell = planner.client.robot_cell # type: RobotCell
77+
planner: AnalyticalKinematicsPlanner = self
78+
robot_cell: RobotCell = planner.client.robot_cell
7979

8080
# Scale Target and get target frame
8181
target = target.normalized_to_meters()
@@ -87,8 +87,9 @@ def _iter_inverse_kinematics_frame_target(self, target, start_state=None, group=
8787

8888
return self.inverse_kinematics_ordered(target_frame, group=group, options=options)
8989

90-
def inverse_kinematics_ordered(self, frame_WCF, group=None, options=None):
91-
# type: (Frame, Optional[str], Optional[Dict]) -> Generator[Configuration | None]
90+
def inverse_kinematics_ordered(
91+
self, frame_WCF: Frame, group: Optional[str] = None, options: Optional[dict] = None
92+
) -> Generator[Configuration | None, None, None]:
9293
"""Calculate the robot's inverse kinematic (IK) for a given frame.
9394
9495
The IK for 6-axis industrial robots returns by default 8 possible solutions.
@@ -138,8 +139,8 @@ def inverse_kinematics_ordered(self, frame_WCF, group=None, options=None):
138139
"""
139140

140141
options = options or {}
141-
planner = self # type: AnalyticalKinematicsPlanner
142-
robot_cell = planner.client.robot_cell # type: RobotCell
142+
planner: AnalyticalKinematicsPlanner = self
143+
robot_cell: RobotCell = planner.client.robot_cell
143144
solver = planner.kinematics_solver
144145

145146
keep_order = options.get("keep_order", False)

src/compas_fab/backends/kinematics/backend_features/analytical_set_robot_cell.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,15 @@
1-
from typing import Optional
2-
31
from copy import deepcopy
2+
from typing import Optional
43

54
from compas_fab.backends.interfaces import SetRobotCell
65
from compas_fab.robots import RobotCell
76
from compas_fab.robots import RobotCellState
87

98

109
class AnalyticalSetRobotCell(SetRobotCell):
11-
def set_robot_cell(self, robot_cell : RobotCell, robot_cell_state : RobotCellState = None, options : Optional[dict] = None):
10+
def set_robot_cell(
11+
self, robot_cell: RobotCell, robot_cell_state: RobotCellState = None, options: Optional[dict] = None
12+
):
1213
"""Pass the models in the robot cell to the Analytical Planner.
1314
1415
The planner will use the tool information for frame transformation.

src/compas_fab/backends/kinematics/solvers/analytical_kinematics.py

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,5 @@
11
from typing import Optional
2+
23
from compas.geometry import Frame
34

45

@@ -32,13 +33,18 @@ class AnalyticalKinematics(object):
3233
Defaults to no offset.
3334
"""
3435

35-
def __init__(self, base_frame : Optional[Frame] = None, flange_frame : Optional[Frame] = None, joint_offsets : Optional[list[float]] = None):
36+
def __init__(
37+
self,
38+
base_frame: Optional[Frame] = None,
39+
flange_frame: Optional[Frame] = None,
40+
joint_offsets: Optional[list[float]] = None,
41+
):
3642
super(AnalyticalKinematics, self).__init__()
3743
self.base_frame = base_frame
3844
self.flange_frame = flange_frame
3945
self.joint_offsets = joint_offsets
4046

41-
def forward(self, joint_values : list[float]) -> Frame:
47+
def forward(self, joint_values: list[float]) -> Frame:
4248
"""Calculate the forward kinematics for the given joint configuration.
4349
4450
Parameters
@@ -54,7 +60,7 @@ def forward(self, joint_values : list[float]) -> Frame:
5460
"""
5561
pass
5662

57-
def inverse(self, frame_rcf : Frame) -> list[list[float]]:
63+
def inverse(self, frame_rcf: Frame) -> list[list[float]]:
5864
"""Calculate the inverse kinematics for the given end-effector frame.
5965
6066
Parameters

src/compas_fab/backends/kinematics/solvers/offset_wrist.py

Lines changed: 2 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -7,20 +7,12 @@
77
from math import sin
88
from math import sqrt
99

10-
from compas import IPY
1110
from compas.geometry import Frame
1211

1312
from compas_fab.utilities import sign
1413

15-
if not IPY:
16-
from typing import TYPE_CHECKING
1714

18-
if TYPE_CHECKING: # pragma: no cover
19-
from typing import List # noqa: F401
20-
21-
22-
def forward_kinematics_offset_wrist(joint_values, params):
23-
# type: (List[float], List[float]) -> Frame
15+
def forward_kinematics_offset_wrist(joint_values: list[float], params: list[float]) -> Frame:
2416
"""Forward kinematics function for offset wrist 6-axis robots.
2517
2618
Parameters
@@ -73,8 +65,7 @@ def forward_kinematics_offset_wrist(joint_values, params):
7365
return frame
7466

7567

76-
def inverse_kinematics_offset_wrist(frame, params, q6_des=0.0):
77-
# type: (Frame, List[float], float) -> List[List[float]]
68+
def inverse_kinematics_offset_wrist(frame: Frame, params: list[float], q6_des: float = 0.0) -> list[list[float]]:
7869
"""Inverse kinematics function for offset wrist 6-axis robots.
7970
8071
Parameters

src/compas_fab/backends/kinematics/solvers/offset_wrist_kinematics.py

Lines changed: 3 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,9 @@
1-
from compas import IPY
1+
from compas.geometry import Frame
22

33
from .analytical_kinematics import AnalyticalKinematics
44
from .offset_wrist import forward_kinematics_offset_wrist
55
from .offset_wrist import inverse_kinematics_offset_wrist
66

7-
if not IPY:
8-
from typing import TYPE_CHECKING
9-
10-
if TYPE_CHECKING: # pragma: no cover
11-
from typing import List # noqa: F401
12-
13-
from compas.geometry import Frame # noqa: F401
14-
157
# The following parameters for UR robots are taken from the following website:
168
# https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/
179

@@ -78,12 +70,10 @@ def __init__(self, params):
7870
super(OffsetWristKinematics, self).__init__()
7971
self.params = params
8072

81-
def forward(self, joint_values):
82-
# type: (List[float]) -> Frame
73+
def forward(self, joint_values: list[float]) -> Frame:
8374
return forward_kinematics_offset_wrist(joint_values, self.params)
8475

85-
def inverse(self, frame_rcf):
86-
# type: (Frame) -> List[List[float]]
76+
def inverse(self, frame_rcf: Frame) -> list[list[float]]:
8777
return inverse_kinematics_offset_wrist(frame_rcf, self.params)
8878

8979

src/compas_fab/backends/pybullet/backend_features/helpers.py

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,21 @@
11
from math import pi
22

33
from compas_robots.model import Joint
4+
45
from compas_fab.backends import MPMaxJumpError
56

67
__all__ = [
78
"check_max_jump",
89
]
910

1011

11-
def check_max_jump(joint_names : list[str], joint_types : list[int], start_joint_values : list[float], end_joint_values : list[float], options : dict):
12+
def check_max_jump(
13+
joint_names: list[str],
14+
joint_types: list[int],
15+
start_joint_values: list[float],
16+
end_joint_values: list[float],
17+
options: dict,
18+
):
1219
"""Check if the joint positions between two configurations exceed the maximum allowed distance.
1320
1421
Parameters

src/compas_fab/backends/ros/backend_features/move_it_inverse_kinematics.py

Lines changed: 36 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,11 @@
1-
from typing import Optional
21
from typing import TYPE_CHECKING
2+
from typing import Optional
33

4-
from compas_robots import Configuration
4+
from compas.geometry import Frame
55
from compas.tolerance import TOL
66
from compas.utilities import await_callback
7-
from compas.geometry import Frame
7+
from compas_robots import Configuration
8+
89
from compas_fab.backends.exceptions import InverseKinematicsError
910
from compas_fab.backends.interfaces import InverseKinematics
1011
from compas_fab.backends.ros.backend_features.helpers import convert_constraints_to_rosmsg
@@ -48,7 +49,13 @@ def __init__(self):
4849
"/compute_ik", "GetPositionIK", GetPositionIKRequest, GetPositionIKResponse, validate_response
4950
)
5051

51-
def inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_cell_state : "RobotCellState", group : Optional[str] = None, options : Optional[dict] = None):
52+
def inverse_kinematics(
53+
self,
54+
target: FrameTarget | PointAxisTarget,
55+
robot_cell_state: "RobotCellState",
56+
group: Optional[str] = None,
57+
options: Optional[dict] = None,
58+
):
5259
"""Calculate the robot's inverse kinematic for a given target.
5360
5461
The actual implementation can be found in the :meth:`iter_inverse_kinematics` method.
@@ -96,8 +103,8 @@ def inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_cell_
96103
97104
"""
98105
# Set default group name
99-
planner : MoveItPlanner = self
100-
client : RosClient = planner.client
106+
planner: MoveItPlanner = self
107+
client: RosClient = planner.client
101108
group = group or client.robot_cell.main_group_name
102109

103110
# The caching mechanism is implemented in the iter_inverse_kinematics method
@@ -111,7 +118,13 @@ def inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_cell_
111118

112119
return configuration
113120

114-
def iter_inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_cell_state : "RobotCellState" = None, group : Optional[str] = None, options : Optional[dict] = None):
121+
def iter_inverse_kinematics(
122+
self,
123+
target: FrameTarget | PointAxisTarget,
124+
robot_cell_state: "RobotCellState" = None,
125+
group: Optional[str] = None,
126+
options: Optional[dict] = None,
127+
):
115128
"""Calculate the robot's inverse kinematic for a given target.
116129
117130
The MoveIt inverse kinematics solver make use of the IK solver pre-configured in
@@ -184,9 +197,9 @@ def iter_inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_
184197
One of the possible IK configurations that reaches the target.
185198
186199
"""
187-
planner : MoveItPlanner = self
188-
client : RosClient = planner.client
189-
robot_cell : RobotCell = client.robot_cell
200+
planner: MoveItPlanner = self
201+
client: RosClient = planner.client
202+
robot_cell: RobotCell = client.robot_cell
190203
group = group or robot_cell.main_group_name
191204

192205
# Calling the super class method, which contains input sanity checks and scale normalization
@@ -210,7 +223,9 @@ def iter_inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_
210223
# Insert any checks needed here. No checks at the moment.
211224
yield configuration
212225

213-
def _iter_inverse_kinematics_frame_target(self, target : FrameTarget, robot_cell_state : "RobotCellState", group : str, options : Optional[dict] = None):
226+
def _iter_inverse_kinematics_frame_target(
227+
self, target: FrameTarget, robot_cell_state: "RobotCellState", group: str, options: Optional[dict] = None
228+
):
214229
"""Calculate the robot's inverse kinematic for a given frame target.
215230
216231
This function is not exposed to the user and therefore docstrings
@@ -219,9 +234,9 @@ def _iter_inverse_kinematics_frame_target(self, target : FrameTarget, robot_cell
219234
"""
220235

221236
# Housekeeping for intellisense
222-
planner : MoveItPlanner = self
223-
client : RosClient = planner.client
224-
robot_cell : RobotCell = client.robot_cell
237+
planner: MoveItPlanner = self
238+
client: RosClient = planner.client
239+
robot_cell: RobotCell = client.robot_cell
225240

226241
# NOTE: group is not optional in this inner function.
227242
if group not in robot_cell.robot_semantics.groups:
@@ -306,7 +321,13 @@ def _iter_inverse_kinematics_frame_target(self, target : FrameTarget, robot_cell
306321
)
307322

308323
def _inverse_kinematics_async(
309-
self, callback, errback, frame_WCF : Frame, start_configuration : Configuration = None, group : str = None, options : Optional[dict] = None
324+
self,
325+
callback,
326+
errback,
327+
frame_WCF: Frame,
328+
start_configuration: Configuration = None,
329+
group: str = None,
330+
options: Optional[dict] = None,
310331
):
311332
"""Asynchronous handler of MoveIt IK service."""
312333
base_link = options["base_link"]

0 commit comments

Comments
 (0)