Skip to content

Commit 81a91df

Browse files
committed
lint/format
1 parent 84026cc commit 81a91df

11 files changed

Lines changed: 128 additions & 64 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: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,9 @@
77

88

99
class AnalyticalSetRobotCell(SetRobotCell):
10-
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+
):
1113
"""Pass the models in the robot cell to the Analytical Planner.
1214
1315
The planner will use the tool information for frame transformation.

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

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,13 +33,18 @@ class AnalyticalKinematics(object):
3333
Defaults to no offset.
3434
"""
3535

36-
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+
):
3742
super(AnalyticalKinematics, self).__init__()
3843
self.base_frame = base_frame
3944
self.flange_frame = flange_frame
4045
self.joint_offsets = joint_offsets
4146

42-
def forward(self, joint_values : list[float]) -> Frame:
47+
def forward(self, joint_values: list[float]) -> Frame:
4348
"""Calculate the forward kinematics for the given joint configuration.
4449
4550
Parameters
@@ -55,7 +60,7 @@ def forward(self, joint_values : list[float]) -> Frame:
5560
"""
5661
pass
5762

58-
def inverse(self, frame_rcf : Frame) -> list[list[float]]:
63+
def inverse(self, frame_rcf: Frame) -> list[list[float]]:
5964
"""Calculate the inverse kinematics for the given end-effector frame.
6065
6166
Parameters

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
from compas_fab.utilities import sign
1313

1414

15-
def forward_kinematics_offset_wrist(joint_values : list[float], params : list[float]) -> Frame:
15+
def forward_kinematics_offset_wrist(joint_values: list[float], params: list[float]) -> Frame:
1616
"""Forward kinematics function for offset wrist 6-axis robots.
1717
1818
Parameters
@@ -65,7 +65,7 @@ def forward_kinematics_offset_wrist(joint_values : list[float], params : list[fl
6565
return frame
6666

6767

68-
def inverse_kinematics_offset_wrist(frame : Frame, params : list[float], q6_des : float = 0.0) -> list[list[float]]:
68+
def inverse_kinematics_offset_wrist(frame: Frame, params: list[float], q6_des: float = 0.0) -> list[list[float]]:
6969
"""Inverse kinematics function for offset wrist 6-axis robots.
7070
7171
Parameters

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,10 +70,10 @@ def __init__(self, params):
7070
super(OffsetWristKinematics, self).__init__()
7171
self.params = params
7272

73-
def forward(self, joint_values : list[float]) -> Frame:
73+
def forward(self, joint_values: list[float]) -> Frame:
7474
return forward_kinematics_offset_wrist(joint_values, self.params)
7575

76-
def inverse(self, frame_rcf : Frame) -> list[list[float]]:
76+
def inverse(self, frame_rcf: Frame) -> list[list[float]]:
7777
return inverse_kinematics_offset_wrist(frame_rcf, self.params)
7878

7979

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

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,13 @@
99
]
1010

1111

12-
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+
):
1319
"""Check if the joint positions between two configurations exceed the maximum allowed distance.
1420
1521
Parameters

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

Lines changed: 32 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,13 @@ def __init__(self):
4949
"/compute_ik", "GetPositionIK", GetPositionIKRequest, GetPositionIKResponse, validate_response
5050
)
5151

52-
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+
):
5359
"""Calculate the robot's inverse kinematic for a given target.
5460
5561
The actual implementation can be found in the :meth:`iter_inverse_kinematics` method.
@@ -97,8 +103,8 @@ def inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_cell_
97103
98104
"""
99105
# Set default group name
100-
planner : MoveItPlanner = self
101-
client : RosClient = planner.client
106+
planner: MoveItPlanner = self
107+
client: RosClient = planner.client
102108
group = group or client.robot_cell.main_group_name
103109

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

113119
return configuration
114120

115-
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+
):
116128
"""Calculate the robot's inverse kinematic for a given target.
117129
118130
The MoveIt inverse kinematics solver make use of the IK solver pre-configured in
@@ -185,9 +197,9 @@ def iter_inverse_kinematics(self, target : FrameTarget | PointAxisTarget, robot_
185197
One of the possible IK configurations that reaches the target.
186198
187199
"""
188-
planner : MoveItPlanner = self
189-
client : RosClient = planner.client
190-
robot_cell : RobotCell = client.robot_cell
200+
planner: MoveItPlanner = self
201+
client: RosClient = planner.client
202+
robot_cell: RobotCell = client.robot_cell
191203
group = group or robot_cell.main_group_name
192204

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

214-
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+
):
215229
"""Calculate the robot's inverse kinematic for a given frame target.
216230
217231
This function is not exposed to the user and therefore docstrings
@@ -220,9 +234,9 @@ def _iter_inverse_kinematics_frame_target(self, target : FrameTarget, robot_cell
220234
"""
221235

222236
# Housekeeping for intellisense
223-
planner : MoveItPlanner = self
224-
client : RosClient = planner.client
225-
robot_cell : RobotCell = client.robot_cell
237+
planner: MoveItPlanner = self
238+
client: RosClient = planner.client
239+
robot_cell: RobotCell = client.robot_cell
226240

227241
# NOTE: group is not optional in this inner function.
228242
if group not in robot_cell.robot_semantics.groups:
@@ -307,7 +321,13 @@ def _iter_inverse_kinematics_frame_target(self, target : FrameTarget, robot_cell
307321
)
308322

309323
def _inverse_kinematics_async(
310-
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,
311331
):
312332
"""Asynchronous handler of MoveIt IK service."""
313333
base_link = options["base_link"]

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

Lines changed: 27 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,13 @@ class MoveItPlanCartesianMotion(PlanCartesianMotion):
4040
validate_response,
4141
)
4242

43-
def plan_cartesian_motion(self, waypoints : Waypoints, start_state : RobotCellState, group : Optional[str] = None, options : Optional[dict] = None) -> JointTrajectory:
43+
def plan_cartesian_motion(
44+
self,
45+
waypoints: Waypoints,
46+
start_state: RobotCellState,
47+
group: Optional[str] = None,
48+
options: Optional[dict] = None,
49+
) -> JointTrajectory:
4450
"""Calculates a cartesian motion path (linear in tool space).
4551
4652
Parameters
@@ -84,9 +90,9 @@ def plan_cartesian_motion(self, waypoints : Waypoints, start_state : RobotCellSt
8490
:class:`compas_fab.robots.JointTrajectory`
8591
The calculated trajectory.
8692
"""
87-
planner : MoveItPlanner = self
88-
client : RosClient = planner.client
89-
robot_cell : RobotCell = client.robot_cell
93+
planner: MoveItPlanner = self
94+
client: RosClient = planner.client
95+
robot_cell: RobotCell = client.robot_cell
9096

9197
options = options or {}
9298
kwargs = {}
@@ -115,15 +121,21 @@ def plan_cartesian_motion(self, waypoints : Waypoints, start_state : RobotCellSt
115121
raise TypeError("Unsupported waypoints type {} for MoveIt planning backend.".format(type(waypoints)))
116122

117123
def plan_cartesian_motion_with_frame_waypoints_async(
118-
self, callback, errback, waypoints : FrameWaypoints, start_state : RobotCellState, group : Optional[str] = None, options : Optional[dict] = None
124+
self,
125+
callback,
126+
errback,
127+
waypoints: FrameWaypoints,
128+
start_state: RobotCellState,
129+
group: Optional[str] = None,
130+
options: Optional[dict] = None,
119131
):
120132
"""Asynchronous handler of MoveIt cartesian motion planner service.
121133
122134
:class:`compas_fab.robots.FrameWaypoints` are converted to :class:`compas_fab.backends.ros.messages.Pose` that is native to ROS communication
123135
124136
"""
125-
planner : MoveItPlanner = self
126-
client : RosClient = planner.client
137+
planner: MoveItPlanner = self
138+
client: RosClient = planner.client
127139

128140
joints = options["joints"]
129141

@@ -136,7 +148,7 @@ def plan_cartesian_motion_with_frame_waypoints_async(
136148

137149
# We are calling the synchronous function here for simplicity.
138150
planner.set_robot_cell_state(start_state)
139-
planning_scene : PlanningScene = planner.get_planning_scene()
151+
planning_scene: PlanningScene = planner.get_planning_scene()
140152
start_state = planning_scene.robot_state
141153

142154
# start_configuration = start_state.robot_configuration
@@ -176,7 +188,13 @@ def response_handler(response):
176188
self.GET_CARTESIAN_PATH(client, request, response_handler, errback)
177189

178190
def plan_cartesian_motion_with_point_axis_waypoints_async(
179-
self, callback, errback, waypoints : PointAxisWaypoints, start_state : RobotCellState, group : Optional[str] = None, options : Optional[dict] = None
191+
self,
192+
callback,
193+
errback,
194+
waypoints: PointAxisWaypoints,
195+
start_state: RobotCellState,
196+
group: Optional[str] = None,
197+
options: Optional[dict] = None,
180198
):
181199
"""Asynchronous handler of MoveIt cartesian motion planner service.
182200

src/compas_fab/robots/reachability_map/reachability_map.py

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
if TYPE_CHECKING:
1515
from compas_fab.backends.interfaces import PlannerInterface
1616

17+
1718
class ReachabilityMap(Data):
1819
"""The ReachabilityMap describes the reachability of a robot.
1920
@@ -45,7 +46,14 @@ def __init__(self, frames=None, configurations=None, name=None):
4546
self.frames = frames or [] # 2D
4647
self.configurations = configurations or [] # 3D
4748

48-
def calculate(self, frame_generator : Generator, planner : "PlannerInterface", robot_cell_state : RobotCellState, target_mode : TargetMode, ik_options : Optional[dict] = None):
49+
def calculate(
50+
self,
51+
frame_generator: Generator,
52+
planner: "PlannerInterface",
53+
robot_cell_state: RobotCellState,
54+
target_mode: TargetMode,
55+
ik_options: Optional[dict] = None,
56+
):
4957
"""Calculates the reachability map for a robot cell.
5058
5159
The robot_cell must be set in the planner before calling this function by calling

src/compas_fab/scene/base_robot_cell_object.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -55,9 +55,9 @@ def __init__(self, draw_visual=True, draw_collision=False, native_scale=1.0, *ar
5555

5656
# Native Geometry handles
5757
# robot_model_object = self._get_robot_model_object()
58-
self._robot_model_scene_object : Optional[BaseRobotModelObject] = None
59-
self._rigid_body_scene_objects : dict[str, BaseRigidBodyObject] = {}
60-
self._tool_scene_objects : dict[str, BaseRobotModelObject] = {}
58+
self._robot_model_scene_object: Optional[BaseRobotModelObject] = None
59+
self._rigid_body_scene_objects: dict[str, BaseRigidBodyObject] = {}
60+
self._tool_scene_objects: dict[str, BaseRobotModelObject] = {}
6161

6262
@property
6363
def robot_cell(self) -> RobotCell:

0 commit comments

Comments
 (0)