Skip to content

Commit f5a4d7c

Browse files
authored
Merge pull request #375 from compas-dev/use_tcf_if_tool_attached
Use attached tool's frame for all planning operations if any tool is attached
2 parents 3d6b822 + e776a83 commit f5a4d7c

File tree

5 files changed

+204
-84
lines changed

5 files changed

+204
-84
lines changed

CHANGELOG.rst

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,8 @@ Unreleased
1919
**Changed**
2020

2121
* Changed behavior of ``Attach Tool`` GH component to only attach the tool but not add it to the planning scene state.
22-
* Duration class takes floats as ``sec`` variable
22+
* Duration class takes floats as ``sec`` variable.
23+
* Changed the behavior of ``forward_kinematics``, ``inverse_kinematics``, ``iter_inverse_kinematics``, ``plan_cartesian_motion`` and constraints construction methods (``orientation_constraint_from_frame``, ``position_constraint_from_frame``, ``constraints_from_frame``) in ``Robot`` class to use the frame of the attached tool if a tool is attached. This behavior can be reverted back (ie. only calculate T0CF) using the flag ``use_attached_tool_frame`` of all these methods.
2324

2425
**Fixed**
2526

docs/examples/06_backends_kinematics/files/04_cartesian_path_analytic_pybullet.py

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -3,19 +3,21 @@
33

44
from compas_fab.backends import AnalyticalPyBulletClient
55

6-
frames_WCF = [Frame((0.407, 0.073, 0.320), (0.922, 0.000, 0.388), (0.113, 0.956, -0.269)),
7-
Frame((0.404, 0.057, 0.324), (0.919, 0.000, 0.394), (0.090, 0.974, -0.210)),
8-
Frame((0.390, 0.064, 0.315), (0.891, 0.000, 0.454), (0.116, 0.967, -0.228)),
9-
Frame((0.388, 0.079, 0.309), (0.881, 0.000, 0.473), (0.149, 0.949, -0.278)),
10-
Frame((0.376, 0.087, 0.299), (0.850, 0.000, 0.528), (0.184, 0.937, -0.296))]
6+
frames_WCF = [
7+
Frame((0.407, 0.073, 0.320), (0.922, 0.000, 0.388), (0.113, 0.956, -0.269)),
8+
Frame((0.404, 0.057, 0.324), (0.919, 0.000, 0.394), (0.090, 0.974, -0.210)),
9+
Frame((0.390, 0.064, 0.315), (0.891, 0.000, 0.454), (0.116, 0.967, -0.228)),
10+
Frame((0.388, 0.079, 0.309), (0.881, 0.000, 0.473), (0.149, 0.949, -0.278)),
11+
Frame((0.376, 0.087, 0.299), (0.850, 0.000, 0.528), (0.184, 0.937, -0.296)),
12+
]
1113

12-
with AnalyticalPyBulletClient(connection_type='direct') as client:
14+
with AnalyticalPyBulletClient(connection_type="direct") as client:
1315
robot = client.load_ur5(load_geometry=True)
1416

1517
options = {"solver": "ur5", "check_collision": True}
1618
start_configuration = list(robot.iter_inverse_kinematics(frames_WCF[0], options=options))[-1]
1719
trajectory = robot.plan_cartesian_motion(frames_WCF, start_configuration=start_configuration, options=options)
18-
assert(trajectory.fraction == 1.)
20+
assert trajectory.fraction == 1.0
1921

2022
j = [c.joint_values for c in trajectory.points]
2123
plt.plot(j)

src/compas_fab/robots/robot.py

Lines changed: 53 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -940,7 +940,7 @@ def ensure_geometry(self):
940940
# constraints
941941
# ==========================================================================
942942

943-
def orientation_constraint_from_frame(self, frame_WCF, tolerances_axes, group=None):
943+
def orientation_constraint_from_frame(self, frame_WCF, tolerances_axes, group=None, use_attached_tool_frame=True):
944944
r"""Create an orientation constraint from a frame on the group's end-effector link.
945945
946946
Parameters
@@ -953,6 +953,9 @@ def orientation_constraint_from_frame(self, frame_WCF, tolerances_axes, group=No
953953
group: :obj:`str`, optional
954954
The planning group for which we specify the constraint. Defaults to
955955
the robot's main planning group.
956+
use_attached_tool_frame : :obj:`bool`, optional
957+
If ``True`` and there is a tool attached to the planning group, it will use its TCF
958+
instead of the T0CF to create the constraints. Defaults to ``True``.
956959
957960
Returns
958961
-------
@@ -982,16 +985,21 @@ def orientation_constraint_from_frame(self, frame_WCF, tolerances_axes, group=No
982985
OrientationConstraint('ee_link', [0.5, 0.5, 0.5, 0.5], [0.017453292519943295, 0.017453292519943295, 0.017453292519943295], 1.0)
983986
"""
984987

988+
attached_tool = self.attached_tools.get(group)
989+
if use_attached_tool_frame and attached_tool:
990+
frame_WCF = self.from_tcf_to_t0cf([frame_WCF], group)[0]
991+
985992
ee_link = self.get_end_effector_link_name(group)
986993

987994
tolerances_axes = list(tolerances_axes)
988995
if len(tolerances_axes) == 1:
989996
tolerances_axes *= 3
990997
elif len(tolerances_axes) != 3:
991998
raise ValueError("Must give either one or 3 values")
999+
9921000
return OrientationConstraint(ee_link, frame_WCF.quaternion, tolerances_axes)
9931001

994-
def position_constraint_from_frame(self, frame_WCF, tolerance_position, group=None):
1002+
def position_constraint_from_frame(self, frame_WCF, tolerance_position, group=None, use_attached_tool_frame=True):
9951003
"""Create a position constraint from a frame on the group's end-effector link.
9961004
9971005
Parameters
@@ -1004,6 +1012,9 @@ def position_constraint_from_frame(self, frame_WCF, tolerance_position, group=No
10041012
group: :obj:`str`, optional
10051013
The planning group for which we specify the constraint. Defaults to
10061014
the robot's main planning group.
1015+
use_attached_tool_frame : :obj:`bool`, optional
1016+
If ``True`` and there is a tool attached to the planning group, it will use its TCF
1017+
instead of the T0CF to create the constraints. Defaults to ``True``.
10071018
10081019
Returns
10091020
-------
@@ -1032,11 +1043,15 @@ def position_constraint_from_frame(self, frame_WCF, tolerance_position, group=No
10321043
PositionConstraint('ee_link', BoundingVolume(2, Sphere(Point(0.400, 0.300, 0.400), 0.001)), 1.0)
10331044
"""
10341045

1046+
attached_tool = self.attached_tools.get(group)
1047+
if use_attached_tool_frame and attached_tool:
1048+
frame_WCF = self.from_tcf_to_t0cf([frame_WCF], group)[0]
1049+
10351050
ee_link = self.get_end_effector_link_name(group)
10361051
sphere = Sphere(frame_WCF.point, tolerance_position)
10371052
return PositionConstraint.from_sphere(ee_link, sphere)
10381053

1039-
def constraints_from_frame(self, frame_WCF, tolerance_position, tolerances_axes, group=None):
1054+
def constraints_from_frame(self, frame_WCF, tolerance_position, tolerances_axes, group=None, use_attached_tool_frame=True):
10401055
r"""Create a position and an orientation constraint from a frame calculated for the group's end-effector link.
10411056
10421057
Parameters
@@ -1052,6 +1067,9 @@ def constraints_from_frame(self, frame_WCF, tolerance_position, tolerances_axes,
10521067
group: :obj:`str`, optional
10531068
The planning group for which we specify the constraint. Defaults to
10541069
the robot's main planning group.
1070+
use_attached_tool_frame : :obj:`bool`, optional
1071+
If ``True`` and there is a tool attached to the planning group, it will use its TCF
1072+
instead of the T0CF to create the constraints. Defaults to ``True``.
10551073
10561074
Returns
10571075
-------
@@ -1084,8 +1102,8 @@ def constraints_from_frame(self, frame_WCF, tolerance_position, tolerances_axes,
10841102
[PositionConstraint('ee_link', BoundingVolume(2, Sphere(Point(0.400, 0.300, 0.400), 0.001)), 1.0),
10851103
OrientationConstraint('ee_link', [0.5, 0.5, 0.5, 0.5], [0.017453292519943295, 0.017453292519943295, 0.017453292519943295], 1.0)]
10861104
"""
1087-
pc = self.position_constraint_from_frame(frame_WCF, tolerance_position, group)
1088-
oc = self.orientation_constraint_from_frame(frame_WCF, tolerances_axes, group)
1105+
pc = self.position_constraint_from_frame(frame_WCF, tolerance_position, group, use_attached_tool_frame)
1106+
oc = self.orientation_constraint_from_frame(frame_WCF, tolerances_axes, group, use_attached_tool_frame)
10891107
return [pc, oc]
10901108

10911109
def constraints_from_configuration(self, configuration, tolerances_above, tolerances_below, group=None):
@@ -1164,7 +1182,7 @@ def constraints_from_configuration(self, configuration, tolerances_above, tolera
11641182
# services
11651183
# ==========================================================================
11661184

1167-
def inverse_kinematics(self, frame_WCF, start_configuration=None, group=None, return_full_configuration=False, options=None):
1185+
def inverse_kinematics(self, frame_WCF, start_configuration=None, group=None, return_full_configuration=False, use_attached_tool_frame=True, options=None):
11681186
"""Calculate the robot's inverse kinematic for a given frame.
11691187
11701188
The inverse kinematic solvers are implemented as generators in order to fit both analytic
@@ -1190,6 +1208,9 @@ def inverse_kinematics(self, frame_WCF, start_configuration=None, group=None, re
11901208
return_full_configuration : :obj:`bool`, optional
11911209
If ``True``, returns a full configuration with all joint values
11921210
specified, including passive ones if available. Defaults to ``False``.
1211+
use_attached_tool_frame : :obj:`bool`, optional
1212+
If ``True`` and there is a tool attached to the planning group, it will use its TCF
1213+
instead of the T0CF to calculate IK. Defaults to ``True``.
11931214
options: :obj:`dict`, optional
11941215
Dictionary containing the key-value pairs of additional options.
11951216
The valid options are specific to the backend in use.
@@ -1221,13 +1242,13 @@ def inverse_kinematics(self, frame_WCF, start_configuration=None, group=None, re
12211242
if solution is not None:
12221243
return solution
12231244

1224-
solutions = self.iter_inverse_kinematics(frame_WCF, start_configuration, group, return_full_configuration, options)
1245+
solutions = self.iter_inverse_kinematics(frame_WCF, start_configuration, group, return_full_configuration, use_attached_tool_frame, options)
12251246
self._current_ik["request_id"] = request_id
12261247
self._current_ik["solutions"] = solutions
12271248

12281249
return next(solutions)
12291250

1230-
def iter_inverse_kinematics(self, frame_WCF, start_configuration=None, group=None, return_full_configuration=False, options=None):
1251+
def iter_inverse_kinematics(self, frame_WCF, start_configuration=None, group=None, return_full_configuration=False, use_attached_tool_frame=True, options=None):
12311252
"""Iterate over the inverse kinematic solutions of a robot.
12321253
12331254
This method exposes the generator-based inverse kinematic solvers. Analytics solvers will return
@@ -1250,6 +1271,9 @@ def iter_inverse_kinematics(self, frame_WCF, start_configuration=None, group=Non
12501271
return_full_configuration : :obj:`bool`, optional
12511272
If ``True``, returns a full configuration with all joint values
12521273
specified, including passive ones if available. Defaults to ``False``.
1274+
use_attached_tool_frame : :obj:`bool`, optional
1275+
If ``True`` and there is a tool attached to the planning group, it will use its TCF
1276+
instead of the T0CF to calculate IK. Defaults to ``True``.
12531277
options: :obj:`dict`, optional
12541278
Dictionary containing the key-value pairs of additional options.
12551279
The valid options are specific to the backend in use.
@@ -1281,6 +1305,10 @@ def iter_inverse_kinematics(self, frame_WCF, start_configuration=None, group=Non
12811305

12821306
start_configuration, start_configuration_scaled = self._check_full_configuration_and_scale(start_configuration)
12831307

1308+
attached_tool = self.attached_tools.get(group)
1309+
if use_attached_tool_frame and attached_tool:
1310+
frame_WCF = self.from_tcf_to_t0cf([frame_WCF], group)[0]
1311+
12841312
frame_WCF_scaled = frame_WCF.copy()
12851313
frame_WCF_scaled.point /= self.scale_factor # must be in meters
12861314

@@ -1329,7 +1357,7 @@ def inverse_kinematics_deprecated(
13291357
),
13301358
)
13311359

1332-
def forward_kinematics(self, configuration, group=None, options=None):
1360+
def forward_kinematics(self, configuration, group=None, use_attached_tool_frame=True, options=None):
13331361
"""Calculate the robot's forward kinematic.
13341362
13351363
Parameters
@@ -1341,6 +1369,9 @@ def forward_kinematics(self, configuration, group=None, options=None):
13411369
group: obj:`str`, optional
13421370
The planning group used for the calculation. Defaults to the robot's
13431371
main planning group.
1372+
use_attached_tool_frame : :obj:`bool`, optional
1373+
If ``True`` and there is a tool attached to the planning group, FK will return
1374+
the TCF of the attached tool instead of the T0CF. Defaults to ``True``.
13441375
options: obj:`dict`, optional
13451376
Dictionary containing the following key-value pairs:
13461377
@@ -1409,12 +1440,17 @@ def forward_kinematics(self, configuration, group=None, options=None):
14091440

14101441
# Scale and return
14111442
frame_WCF.point *= self.scale_factor
1443+
1444+
attached_tool = self.attached_tools.get(group)
1445+
if use_attached_tool_frame and attached_tool:
1446+
frame_WCF = self.from_t0cf_to_tcf([frame_WCF], group)[0]
1447+
14121448
return frame_WCF
14131449

14141450
def forward_kinematics_deprecated(self, configuration, group=None, backend=None, ee_link=None):
14151451
return self.forward_kinematics(configuration, group, options=dict(solver=backend, link=ee_link))
14161452

1417-
def plan_cartesian_motion(self, frames_WCF, start_configuration=None, group=None, options=None):
1453+
def plan_cartesian_motion(self, frames_WCF, start_configuration=None, group=None, use_attached_tool_frame=True, options=None):
14181454
"""Calculate a cartesian motion path (linear in tool space).
14191455
14201456
Parameters
@@ -1428,6 +1464,9 @@ def plan_cartesian_motion(self, frames_WCF, start_configuration=None, group=None
14281464
group : :obj:`str`, optional
14291465
The planning group used for calculation. Defaults to the robot's
14301466
main planning group.
1467+
use_attached_tool_frame : :obj:`bool`, optional
1468+
If ``True`` and there is a tool attached to the planning group, it will use its TCF
1469+
instead of the T0CF to calculate cartesian paths. Defaults to ``True``.
14311470
options : :obj:`dict`, optional
14321471
Dictionary containing the following key-value pairs:
14331472
@@ -1484,6 +1523,10 @@ def plan_cartesian_motion(self, frames_WCF, start_configuration=None, group=None
14841523
# that all configurable joints of the whole robot are defined for planning.
14851524
start_configuration, start_configuration_scaled = self._check_full_configuration_and_scale(start_configuration)
14861525

1526+
attached_tool = self.attached_tools.get(group)
1527+
if use_attached_tool_frame and attached_tool:
1528+
frames_WCF = self.from_tcf_to_t0cf(frames_WCF, group)
1529+
14871530
frames_WCF_scaled = []
14881531
for frame in frames_WCF:
14891532
frames_WCF_scaled.append(Frame(frame.point * 1.0 / self.scale_factor, frame.xaxis, frame.yaxis))

tests/backends/kinematics/test_inverse_kinematics.py

Lines changed: 48 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,14 @@
44

55
import compas_fab
66
from compas_fab.backends import AnalyticalInverseKinematics
7+
from compas_fab.robots import Tool
78
from compas_fab.robots.ur5 import Robot
89

910
if not compas.IPY:
1011
from compas_fab.backends import AnalyticalPyBulletClient
1112

12-
urdf_filename = compas_fab.get('universal_robot/ur_description/urdf/ur5.urdf')
13-
srdf_filename = compas_fab.get('universal_robot/ur5_moveit_config/config/ur5.srdf')
13+
urdf_filename = compas_fab.get("universal_robot/ur_description/urdf/ur5.urdf")
14+
srdf_filename = compas_fab.get("universal_robot/ur5_moveit_config/config/ur5.srdf")
1415

1516

1617
def test_inverse_kinematics():
@@ -19,10 +20,10 @@ def test_inverse_kinematics():
1920
frame_WCF = Frame((0.381, 0.093, 0.382), (0.371, -0.292, -0.882), (0.113, 0.956, -0.269))
2021
# set the solver later
2122
solutions = list(ik.inverse_kinematics(robot, frame_WCF, start_configuration=None, group=None, options={"solver": "ur5"}))
22-
assert(len(solutions) == 8)
23+
assert len(solutions) == 8
2324
joint_positions, _ = solutions[0]
2425
correct = Configuration.from_revolute_values((0.022, 4.827, 1.508, 1.126, 1.876, 3.163))
25-
assert(correct.close_to(Configuration.from_revolute_values(joint_positions)))
26+
assert correct.close_to(Configuration.from_revolute_values(joint_positions))
2627

2728

2829
def test_inverse_kinematics2():
@@ -31,37 +32,69 @@ def test_inverse_kinematics2():
3132
frame_WCF = Frame((0.381, 0.093, 0.382), (0.371, -0.292, -0.882), (0.113, 0.956, -0.269))
3233
# set the solver later
3334
solutions = list(ik.inverse_kinematics(robot, frame_WCF, start_configuration=None, group=None))
34-
assert(len(solutions) == 8)
35+
assert len(solutions) == 8
3536
joint_positions, _ = solutions[0]
3637
correct = Configuration.from_revolute_values((0.022, 4.827, 1.508, 1.126, 1.876, 3.163))
37-
assert(correct.close_to(Configuration.from_revolute_values(joint_positions)))
38+
assert correct.close_to(Configuration.from_revolute_values(joint_positions))
3839

3940

4041
def test_kinematics_client():
4142
if compas.IPY:
4243
return
4344
frame_WCF = Frame((0.381, 0.093, 0.382), (0.371, -0.292, -0.882), (0.113, 0.956, -0.269))
44-
with AnalyticalPyBulletClient(connection_type='direct') as client:
45+
with AnalyticalPyBulletClient(connection_type="direct") as client:
4546
robot = client.load_robot(urdf_filename)
4647
client.load_semantics(robot, srdf_filename)
4748
solutions = list(robot.iter_inverse_kinematics(frame_WCF, options={"solver": "ur5", "check_collision": True, "keep_order": False}))
48-
assert(len(solutions) == 5)
49+
assert len(solutions) == 5
50+
51+
52+
def test_kinematics_client_with_attached_tool_but_disabled_usage_of_tcf():
53+
if compas.IPY:
54+
return
55+
frame_WCF = Frame((0.381, 0.093, 0.382), (0.371, -0.292, -0.882), (0.113, 0.956, -0.269))
56+
with AnalyticalPyBulletClient(connection_type="direct") as client:
57+
robot = client.load_robot(urdf_filename)
58+
client.load_semantics(robot, srdf_filename)
59+
60+
tool_frame = Frame([0.0, 0, 0], [0, 1, 0], [0, 0, 1])
61+
robot.attach_tool(Tool(visual=None, frame_in_tool0_frame=tool_frame))
62+
63+
solutions = list(robot.iter_inverse_kinematics(frame_WCF, use_attached_tool_frame=False, options={"solver": "ur5", "check_collision": True, "keep_order": False}))
64+
assert len(solutions) == 5
65+
66+
67+
def test_kinematics_client_with_attached_tool():
68+
if compas.IPY:
69+
return
70+
frame_WCF = Frame((0.381, 0.093, 0.382), (0.371, -0.292, -0.882), (0.113, 0.956, -0.269))
71+
with AnalyticalPyBulletClient(connection_type="direct") as client:
72+
robot = client.load_robot(urdf_filename)
73+
client.load_semantics(robot, srdf_filename)
74+
75+
tool_frame = Frame([0, 0, 0.6], [1, 0, 0], [0, 1, 0])
76+
robot.attach_tool(Tool(visual=None, frame_in_tool0_frame=tool_frame))
77+
78+
solutions = list(robot.iter_inverse_kinematics(frame_WCF, options={"solver": "ur5", "check_collision": True, "keep_order": False}))
79+
assert len(solutions) == 4
4980

5081

5182
def test_kinematics_cartesian():
5283
if compas.IPY:
5384
return
54-
frames_WCF = [Frame((0.407, 0.073, 0.320), (0.922, 0.000, 0.388), (0.113, 0.956, -0.269)),
55-
Frame((0.404, 0.057, 0.324), (0.919, 0.000, 0.394), (0.090, 0.974, -0.210)),
56-
Frame((0.390, 0.064, 0.315), (0.891, 0.000, 0.454), (0.116, 0.967, -0.228)),
57-
Frame((0.388, 0.079, 0.309), (0.881, 0.000, 0.473), (0.149, 0.949, -0.278)),
58-
Frame((0.376, 0.087, 0.299), (0.850, 0.000, 0.528), (0.184, 0.937, -0.296))]
85+
frames_WCF = [
86+
Frame((0.407, 0.073, 0.320), (0.922, 0.000, 0.388), (0.113, 0.956, -0.269)),
87+
Frame((0.404, 0.057, 0.324), (0.919, 0.000, 0.394), (0.090, 0.974, -0.210)),
88+
Frame((0.390, 0.064, 0.315), (0.891, 0.000, 0.454), (0.116, 0.967, -0.228)),
89+
Frame((0.388, 0.079, 0.309), (0.881, 0.000, 0.473), (0.149, 0.949, -0.278)),
90+
Frame((0.376, 0.087, 0.299), (0.850, 0.000, 0.528), (0.184, 0.937, -0.296)),
91+
]
5992

60-
with AnalyticalPyBulletClient(connection_type='direct') as client:
93+
with AnalyticalPyBulletClient(connection_type="direct") as client:
6194
robot = client.load_robot(urdf_filename)
6295
client.load_semantics(robot, srdf_filename)
6396

6497
options = {"solver": "ur5", "check_collision": True}
6598
start_configuration = list(robot.iter_inverse_kinematics(frames_WCF[0], options=options))[-1]
6699
trajectory = robot.plan_cartesian_motion(frames_WCF, start_configuration=start_configuration, options=options)
67-
assert(trajectory.fraction == 1.)
100+
assert trajectory.fraction == 1.0

0 commit comments

Comments
 (0)