Skip to content

Commit af8f1f6

Browse files
committed
formatting
1 parent 9f442e9 commit af8f1f6

File tree

1 file changed

+44
-12
lines changed

1 file changed

+44
-12
lines changed

src/compas_fab/robots/robot.py

Lines changed: 44 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -549,7 +549,9 @@ def get_group_configuration(self, group, full_configuration):
549549
:class:`Configuration`
550550
The configuration of the group.
551551
"""
552-
full_configuration = self._check_full_configuration_and_scale(full_configuration)[0] # adds joint_names to full_configuration and makes copy
552+
full_configuration = self._check_full_configuration_and_scale(full_configuration)[
553+
0
554+
] # adds joint_names to full_configuration and makes copy
553555
group_joint_names = self.get_configurable_joint_names(group)
554556
values = [full_configuration[name] for name in group_joint_names]
555557
return Configuration(values, self.get_configurable_joint_types(group), group_joint_names)
@@ -583,7 +585,9 @@ def merge_group_with_full_configuration(self, group_configuration, full_configur
583585
if not group_configuration.joint_names:
584586
group_configuration.joint_names = self.get_configurable_joint_names(group)
585587

586-
full_configuration = self._check_full_configuration_and_scale(full_configuration)[0] # adds joint_names to full_configuration and makes copy
588+
full_configuration = self._check_full_configuration_and_scale(full_configuration)[
589+
0
590+
] # adds joint_names to full_configuration and makes copy
587591

588592
full_configuration = full_configuration.merged(group_configuration)
589593
return full_configuration
@@ -654,7 +658,11 @@ def _check_full_configuration_and_scale(self, full_configuration=None):
654658
joint_names = self.get_configurable_joint_names() # full configuration
655659
# full_configuration might have passive joints specified as well, we allow this.
656660
if len(joint_names) > len(full_configuration.joint_values):
657-
raise ValueError("Please pass a configuration with {} values, for all configurable joints of the robot.".format(len(joint_names)))
661+
raise ValueError(
662+
"Please pass a configuration with {} values, for all configurable joints of the robot.".format(
663+
len(joint_names)
664+
)
665+
)
658666
configuration = full_configuration.copy()
659667
if not configuration.joint_names:
660668
configuration.joint_names = joint_names
@@ -1089,7 +1097,9 @@ def position_constraint_from_frame(self, frame_WCF, tolerance_position, group=No
10891097
sphere = Sphere(radius=tolerance_position, point=frame_WCF.point)
10901098
return PositionConstraint.from_sphere(ee_link, sphere)
10911099

1092-
def constraints_from_frame(self, frame_WCF, tolerance_position, tolerances_axes, group=None, use_attached_tool_frame=True):
1100+
def constraints_from_frame(
1101+
self, frame_WCF, tolerance_position, tolerances_axes, group=None, use_attached_tool_frame=True
1102+
):
10931103
r"""Create a position and an orientation constraint from a frame calculated for the group's end-effector link.
10941104
10951105
Parameters
@@ -1201,18 +1211,32 @@ def constraints_from_configuration(self, configuration, tolerances_above, tolera
12011211

12021212
joint_names = self.get_configurable_joint_names(group)
12031213
if len(joint_names) != len(configuration.joint_values):
1204-
raise ValueError("The passed configuration has {} joint_values, the group {} needs however: {}".format(len(configuration.joint_values), group, len(joint_names)))
1214+
raise ValueError(
1215+
"The passed configuration has {} joint_values, the group {} needs however: {}".format(
1216+
len(configuration.joint_values), group, len(joint_names)
1217+
)
1218+
)
12051219
if len(tolerances_above) == 1:
12061220
tolerances_above = tolerances_above * len(joint_names)
12071221
elif len(tolerances_above) != len(configuration.joint_values):
1208-
raise ValueError("The passed configuration has {} joint_values, the tolerances_above however: {}".format(len(configuration.joint_values), len(tolerances_above)))
1222+
raise ValueError(
1223+
"The passed configuration has {} joint_values, the tolerances_above however: {}".format(
1224+
len(configuration.joint_values), len(tolerances_above)
1225+
)
1226+
)
12091227
if len(tolerances_below) == 1:
12101228
tolerances_below = tolerances_below * len(joint_names)
12111229
elif len(tolerances_below) != len(configuration.joint_values):
1212-
raise ValueError("The passed configuration has {} joint_values, the tolerances_below however: {}".format(len(configuration.joint_values), len(tolerances_below)))
1230+
raise ValueError(
1231+
"The passed configuration has {} joint_values, the tolerances_below however: {}".format(
1232+
len(configuration.joint_values), len(tolerances_below)
1233+
)
1234+
)
12131235

12141236
constraints = []
1215-
for name, value, tolerance_above, tolerance_below in zip(joint_names, configuration.joint_values, tolerances_above, tolerances_below):
1237+
for name, value, tolerance_above, tolerance_below in zip(
1238+
joint_names, configuration.joint_values, tolerances_above, tolerances_below
1239+
):
12161240
constraints.append(JointConstraint(name, value, tolerance_above, tolerance_below))
12171241
return constraints
12181242

@@ -1281,14 +1305,18 @@ def inverse_kinematics(
12811305
Configuration((4.045, 5.130, -2.174, -6.098, -5.616, 6.283), (0, 0, 0, 0, 0, 0)) # doctest: +SKIP
12821306
"""
12831307
# Pseudo-memoized sequential calls will re-use iterator if not exhaused
1284-
request_id = "{}-{}-{}-{}-{}".format(str(frame_WCF), str(start_configuration), str(group), str(return_full_configuration), str(options))
1308+
request_id = "{}-{}-{}-{}-{}".format(
1309+
str(frame_WCF), str(start_configuration), str(group), str(return_full_configuration), str(options)
1310+
)
12851311

12861312
if self._current_ik["request_id"] == request_id and self._current_ik["solutions"] is not None:
12871313
solution = next(self._current_ik["solutions"], None)
12881314
if solution is not None:
12891315
return solution
12901316

1291-
solutions = self.iter_inverse_kinematics(frame_WCF, start_configuration, group, return_full_configuration, use_attached_tool_frame, options)
1317+
solutions = self.iter_inverse_kinematics(
1318+
frame_WCF, start_configuration, group, return_full_configuration, use_attached_tool_frame, options
1319+
)
12921320
self._current_ik["request_id"] = request_id
12931321
self._current_ik["solutions"] = solutions
12941322

@@ -1512,7 +1540,9 @@ def forward_kinematics(self, configuration, group=None, use_attached_tool_frame=
15121540
def forward_kinematics_deprecated(self, configuration, group=None, backend=None, ee_link=None):
15131541
return self.forward_kinematics(configuration, group, options=dict(solver=backend, link=ee_link))
15141542

1515-
def plan_cartesian_motion(self, frames_WCF, start_configuration=None, group=None, use_attached_tool_frame=True, options=None):
1543+
def plan_cartesian_motion(
1544+
self, frames_WCF, start_configuration=None, group=None, use_attached_tool_frame=True, options=None
1545+
):
15161546
"""Calculate a cartesian motion path (linear in tool space).
15171547
15181548
Parameters
@@ -1723,7 +1753,9 @@ def plan_motion(self, goal_constraints, start_configuration=None, group=None, op
17231753
>>> tolerances_above = [math.radians(5)] * len(configuration.joint_values)
17241754
>>> tolerances_below = [math.radians(5)] * len(configuration.joint_values)
17251755
>>> group = robot.main_group_name
1726-
>>> goal_constraints = robot.constraints_from_configuration(configuration, tolerances_above, tolerances_below, group)
1756+
>>> goal_constraints = robot.constraints_from_configuration(
1757+
... configuration, tolerances_above, tolerances_below, group
1758+
... )
17271759
>>> trajectory = robot.plan_motion(goal_constraints, start_configuration, group, {"planner_id": "RRTConnect"})
17281760
>>> trajectory.fraction
17291761
1.0

0 commit comments

Comments
 (0)