Skip to content

Commit 0ea8d3b

Browse files
committed
needs skip on every line
1 parent af8f1f6 commit 0ea8d3b

File tree

1 file changed

+43
-35
lines changed

1 file changed

+43
-35
lines changed

src/compas_fab/robots/robot.py

Lines changed: 43 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -1584,23 +1584,23 @@ def plan_cartesian_motion(
15841584
Examples
15851585
--------
15861586
1587-
>>> ros = RosClient() # doctest: +SKIP
1588-
>>> ros.run()
1589-
>>> robot = ros.load_robot()
1590-
>>> frames = [Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0]),\
1587+
>>> ros = RosClient() # doctest: +SKIP # doctest: +SKIP
1588+
>>> ros.run() # doctest: +SKIP
1589+
>>> robot = ros.load_robot() # doctest: +SKIP
1590+
>>> frames = [Frame([0.3, 0.1, 0.5], [1, 0, 0], [0, 1, 0]),\ # doctest: +SKIP
15911591
Frame([0.5, 0.1, 0.6], [1, 0, 0], [0, 1, 0])]
1592-
>>> start_configuration = Configuration.from_revolute_values([-0.042, 0.033, -2.174, 5.282, -1.528, 0.000])
1593-
>>> group = robot.main_group_name
1592+
>>> start_configuration = Configuration.from_revolute_values([-0.042, 0.033, -2.174, 5.282, -1.528, 0.000]) # doctest: +SKIP
1593+
>>> group = robot.main_group_name # doctest: +SKIP
15941594
>>> options = {'max_step': 0.01,\
15951595
'jump_threshold': 1.57,\
1596-
'avoid_collisions': True}
1596+
'avoid_collisions': True} # doctest: +SKIP
15971597
>>> trajectory = robot.plan_cartesian_motion(frames,\
15981598
start_configuration,\
15991599
group=group,\
1600-
options=options)
1601-
>>> len(trajectory.points) > 1
1600+
options=options) # doctest: +SKIP
1601+
>>> len(trajectory.points) > 1 # doctest: +SKIP
16021602
True
1603-
>>> ros.close()
1603+
>>> ros.close() # doctest: +SKIP
16041604
"""
16051605
options = options or {}
16061606
max_step = options.get("max_step")
@@ -1728,40 +1728,48 @@ def plan_motion(self, goal_constraints, start_configuration=None, group=None, op
17281728
17291729
Using position and orientation constraints:
17301730
1731-
>>> ros = RosClient() # doctest: +SKIP
1732-
>>> ros.run()
1733-
>>> robot = ros.load_robot()
1734-
>>> frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1])
1735-
>>> tolerance_position = 0.001
1736-
>>> tolerances_axes = [math.radians(1)] * 3
1737-
>>> start_configuration = Configuration.from_revolute_values([-0.042, 4.295, 0, -3.327, 4.755, 0.0])
1738-
>>> group = robot.main_group_name
1739-
>>> goal_constraints = robot.constraints_from_frame(frame, tolerance_position, tolerances_axes, group)
1740-
>>> trajectory = robot.plan_motion(goal_constraints, start_configuration, group, {"planner_id": "RRTConnect"})
1741-
>>> trajectory.fraction
1731+
>>> ros = RosClient() # doctest: +SKIP # doctest: +SKIP
1732+
>>> ros.run() # doctest: +SKIP
1733+
>>> robot = ros.load_robot() # doctest: +SKIP
1734+
>>> frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1]) # doctest: +SKIP
1735+
>>> tolerance_position = 0.001 # doctest: +SKIP
1736+
>>> tolerances_axes = [math.radians(1)] * 3 # doctest: +SKIP
1737+
>>> start_configuration = Configuration.from_revolute_values(
1738+
... [-0.042, 4.295, 0, -3.327, 4.755, 0.0]
1739+
... ) # doctest: +SKIP
1740+
>>> group = robot.main_group_name # doctest: +SKIP
1741+
>>> goal_constraints = robot.constraints_from_frame(
1742+
... frame, tolerance_position, tolerances_axes, group
1743+
... ) # doctest: +SKIP
1744+
>>> trajectory = robot.plan_motion(
1745+
... goal_constraints, start_configuration, group, {"planner_id": "RRTConnect"}
1746+
... ) # doctest: +SKIP
1747+
>>> trajectory.fraction # doctest: +SKIP
17421748
1.0
1743-
>>> len(trajectory.points) > 1
1749+
>>> len(trajectory.points) > 1 # doctest: +SKIP
17441750
True
1745-
>>> ros.close()
1751+
>>> ros.close() # doctest: +SKIP
17461752
17471753
Using joint constraints (to the UP configuration):
17481754
1749-
>>> ros = RosClient() # doctest: +SKIP
1750-
>>> ros.run()
1751-
>>> robot = ros.load_robot()
1752-
>>> configuration = Configuration.from_revolute_values([0.0, -1.5707, 0.0, -1.5707, 0.0, 0.0])
1753-
>>> tolerances_above = [math.radians(5)] * len(configuration.joint_values)
1754-
>>> tolerances_below = [math.radians(5)] * len(configuration.joint_values)
1755-
>>> group = robot.main_group_name
1755+
>>> ros = RosClient() # doctest: +SKIP # doctest: +SKIP
1756+
>>> ros.run() # doctest: +SKIP
1757+
>>> robot = ros.load_robot() # doctest: +SKIP
1758+
>>> configuration = Configuration.from_revolute_values([0.0, -1.5707, 0.0, -1.5707, 0.0, 0.0]) # doctest: +SKIP
1759+
>>> tolerances_above = [math.radians(5)] * len(configuration.joint_values) # doctest: +SKIP
1760+
>>> tolerances_below = [math.radians(5)] * len(configuration.joint_values) # doctest: +SKIP
1761+
>>> group = robot.main_group_name # doctest: +SKIP
17561762
>>> goal_constraints = robot.constraints_from_configuration(
17571763
... configuration, tolerances_above, tolerances_below, group
1758-
... )
1759-
>>> trajectory = robot.plan_motion(goal_constraints, start_configuration, group, {"planner_id": "RRTConnect"})
1760-
>>> trajectory.fraction
1764+
... ) # doctest: +SKIP
1765+
>>> trajectory = robot.plan_motion(
1766+
... goal_constraints, start_configuration, group, {"planner_id": "RRTConnect"}
1767+
... ) # doctest: +SKIP
1768+
>>> trajectory.fraction # doctest: +SKIP
17611769
1.0
1762-
>>> len(trajectory.points) > 1
1770+
>>> len(trajectory.points) > 1 # doctest: +SKIP
17631771
True
1764-
>>> ros.close()
1772+
>>> ros.close() # doctest: +SKIP
17651773
"""
17661774
options = options or {}
17671775
path_constraints = options.get("path_constraints")

0 commit comments

Comments
 (0)