Skip to content

Commit 9f442e9

Browse files
committed
skip ros integration tests
1 parent fb3d9b7 commit 9f442e9

File tree

1 file changed

+15
-47
lines changed

1 file changed

+15
-47
lines changed

src/compas_fab/robots/robot.py

Lines changed: 15 additions & 47 deletions
Original file line numberDiff line numberDiff line change
@@ -549,9 +549,7 @@ 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)[
553-
0
554-
] # adds joint_names to full_configuration and makes copy
552+
full_configuration = self._check_full_configuration_and_scale(full_configuration)[0] # adds joint_names to full_configuration and makes copy
555553
group_joint_names = self.get_configurable_joint_names(group)
556554
values = [full_configuration[name] for name in group_joint_names]
557555
return Configuration(values, self.get_configurable_joint_types(group), group_joint_names)
@@ -585,9 +583,7 @@ def merge_group_with_full_configuration(self, group_configuration, full_configur
585583
if not group_configuration.joint_names:
586584
group_configuration.joint_names = self.get_configurable_joint_names(group)
587585

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

592588
full_configuration = full_configuration.merged(group_configuration)
593589
return full_configuration
@@ -658,11 +654,7 @@ def _check_full_configuration_and_scale(self, full_configuration=None):
658654
joint_names = self.get_configurable_joint_names() # full configuration
659655
# full_configuration might have passive joints specified as well, we allow this.
660656
if len(joint_names) > len(full_configuration.joint_values):
661-
raise ValueError(
662-
"Please pass a configuration with {} values, for all configurable joints of the robot.".format(
663-
len(joint_names)
664-
)
665-
)
657+
raise ValueError("Please pass a configuration with {} values, for all configurable joints of the robot.".format(len(joint_names)))
666658
configuration = full_configuration.copy()
667659
if not configuration.joint_names:
668660
configuration.joint_names = joint_names
@@ -1097,9 +1089,7 @@ def position_constraint_from_frame(self, frame_WCF, tolerance_position, group=No
10971089
sphere = Sphere(radius=tolerance_position, point=frame_WCF.point)
10981090
return PositionConstraint.from_sphere(ee_link, sphere)
10991091

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

12121202
joint_names = self.get_configurable_joint_names(group)
12131203
if len(joint_names) != len(configuration.joint_values):
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-
)
1204+
raise ValueError("The passed configuration has {} joint_values, the group {} needs however: {}".format(len(configuration.joint_values), group, len(joint_names)))
12191205
if len(tolerances_above) == 1:
12201206
tolerances_above = tolerances_above * len(joint_names)
12211207
elif len(tolerances_above) != len(configuration.joint_values):
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-
)
1208+
raise ValueError("The passed configuration has {} joint_values, the tolerances_above however: {}".format(len(configuration.joint_values), len(tolerances_above)))
12271209
if len(tolerances_below) == 1:
12281210
tolerances_below = tolerances_below * len(joint_names)
12291211
elif len(tolerances_below) != len(configuration.joint_values):
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-
)
1212+
raise ValueError("The passed configuration has {} joint_values, the tolerances_below however: {}".format(len(configuration.joint_values), len(tolerances_below)))
12351213

12361214
constraints = []
1237-
for name, value, tolerance_above, tolerance_below in zip(
1238-
joint_names, configuration.joint_values, tolerances_above, tolerances_below
1239-
):
1215+
for name, value, tolerance_above, tolerance_below in zip(joint_names, configuration.joint_values, tolerances_above, tolerances_below):
12401216
constraints.append(JointConstraint(name, value, tolerance_above, tolerance_below))
12411217
return constraints
12421218

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

13121286
if self._current_ik["request_id"] == request_id and self._current_ik["solutions"] is not None:
13131287
solution = next(self._current_ik["solutions"], None)
13141288
if solution is not None:
13151289
return solution
13161290

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

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

1543-
def plan_cartesian_motion(
1544-
self, frames_WCF, start_configuration=None, group=None, use_attached_tool_frame=True, options=None
1545-
):
1515+
def plan_cartesian_motion(self, frames_WCF, start_configuration=None, group=None, use_attached_tool_frame=True, options=None):
15461516
"""Calculate a cartesian motion path (linear in tool space).
15471517
15481518
Parameters
@@ -1584,7 +1554,7 @@ def plan_cartesian_motion(
15841554
Examples
15851555
--------
15861556
1587-
>>> ros = RosClient()
1557+
>>> ros = RosClient() # doctest: +SKIP
15881558
>>> ros.run()
15891559
>>> robot = ros.load_robot()
15901560
>>> frames = [Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0]),\
@@ -1728,7 +1698,7 @@ def plan_motion(self, goal_constraints, start_configuration=None, group=None, op
17281698
17291699
Using position and orientation constraints:
17301700
1731-
>>> ros = RosClient()
1701+
>>> ros = RosClient() # doctest: +SKIP
17321702
>>> ros.run()
17331703
>>> robot = ros.load_robot()
17341704
>>> frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1])
@@ -1746,16 +1716,14 @@ def plan_motion(self, goal_constraints, start_configuration=None, group=None, op
17461716
17471717
Using joint constraints (to the UP configuration):
17481718
1749-
>>> ros = RosClient()
1719+
>>> ros = RosClient() # doctest: +SKIP
17501720
>>> ros.run()
17511721
>>> robot = ros.load_robot()
17521722
>>> configuration = Configuration.from_revolute_values([0.0, -1.5707, 0.0, -1.5707, 0.0, 0.0])
17531723
>>> tolerances_above = [math.radians(5)] * len(configuration.joint_values)
17541724
>>> tolerances_below = [math.radians(5)] * len(configuration.joint_values)
17551725
>>> group = robot.main_group_name
1756-
>>> goal_constraints = robot.constraints_from_configuration(
1757-
... configuration, tolerances_above, tolerances_below, group
1758-
... )
1726+
>>> goal_constraints = robot.constraints_from_configuration(configuration, tolerances_above, tolerances_below, group)
17591727
>>> trajectory = robot.plan_motion(goal_constraints, start_configuration, group, {"planner_id": "RRTConnect"})
17601728
>>> trajectory.fraction
17611729
1.0

0 commit comments

Comments
 (0)