-
Notifications
You must be signed in to change notification settings - Fork 33
/
constraints.py
816 lines (688 loc) · 28.9 KB
/
constraints.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
from compas.data import Data
from compas.geometry import Rotation
from compas.geometry import Scale
from compas.geometry import Sphere
from compas_fab.utilities import from_tcf_to_t0cf
__all__ = ["BoundingVolume", "Constraint", "JointConstraint", "OrientationConstraint", "PositionConstraint"]
class BoundingVolume(Data):
"""A container for describing a bounding volume.
Parameters
----------
volume_type
The type of bounding volume, one of :attr:`BoundingVolume.VOLUME_TYPES`.
volume : :class:`compas.datastructures.Mesh` or :class:`compas.geometry.Primitive`
The volume can be either a :class:`compas.geometry.Box`, a
:class:`compas.geometry.Sphere`, or a
:class:`compas.datastructures.Mesh`.
Attributes
----------
volume_type
The type of bounding volume, one of :attr:`BoundingVolume.VOLUME_TYPES`.
volume : :class:`compas.datastructures.Mesh` or :class:`compas.geometry.Primitive`
The volume can be either a :class:`compas.geometry.Box`, a
:class:`compas.geometry.Sphere`, or a
:class:`compas.datastructures.Mesh`.
Notes
-----
`BoundingVolume.BOX`
Box bounding volume type.
`BoundingVolume.SPHERE`
Sphere bounding volume type.
`BoundingVolume.MESH`
Mesh bounding volume type.
`BoundingVolume.VOLUME_TYPES`
List of supported bounding volume types.
"""
#: Box bounding volume type
BOX = 1
#: Sphere bounding volume type
SPHERE = 2
#: Mesh bounding volume type
MESH = 3
#: List of supported volume types
VOLUME_TYPES = (BOX, SPHERE, MESH)
def __init__(self, volume_type, volume):
if volume_type not in self.VOLUME_TYPES:
raise ValueError("Type must be one of {}".format(self.VOLUME_TYPES))
self.type = volume_type
self.volume = volume
def __data__(self):
return {
"volume_type": self.type,
"volume": self.volume,
}
@classmethod
def from_box(cls, box):
"""Create a :class:`BoundingVolume` from a :class:`compas.geometry.Box`.
Parameters
----------
box : :class:`compas.geometry.Box`
Box to define :class:`BoundingVolume` with.
Returns
-------
:class:`BoundingVolume`
Examples
--------
>>> from compas.geometry import Frame
>>> from compas.geometry import Box
>>> from compas_fab.robots import BoundingVolume
>>> box = Box(1., 1., 1.)
>>> bv = BoundingVolume.from_box(box)
>>> bv.type
1
"""
return cls(cls.BOX, box)
@classmethod
def from_sphere(cls, sphere):
"""Create a :class:`BoundingVolume` from a :class:`compas.geometry.Sphere`.
Parameters
----------
sphere : :class:`compas.geometry.Sphere`
Sphere to define :class:`BoundingVolume` with.
Returns
-------
:class:`BoundingVolume`
Examples
--------
>>> from compas.geometry import Sphere
>>> from compas_fab.robots import BoundingVolume
>>> sphere = Sphere(5.0, Frame.worldXY())
>>> bv = BoundingVolume.from_sphere(sphere)
>>> bv.type
2
"""
return cls(cls.SPHERE, sphere)
@classmethod
def from_mesh(cls, mesh):
"""Create a :class:`BoundingVolume` from a :class:`compas.datastructures.Mesh`.
Parameters
----------
mesh : :class:`compas.datastructures.Mesh`
Returns
-------
:class:`BoundingVolume`
Mesh to define :class:`BoundingVolume` with.
Examples
--------
>>> import compas
>>> from compas.datastructures import Mesh
>>> from compas_fab.robots import BoundingVolume
>>> mesh = Mesh.from_obj(compas.get('faces.obj'))
>>> bv = BoundingVolume.from_mesh(Mesh)
>>> bv.type
3
"""
return cls(cls.MESH, mesh)
def scale(self, scale_factor):
"""Scale the volume uniformly.
Parameters
----------
scale_factor : :obj:`float`
Scale factor to use in scaling operation.
"""
S = Scale.from_factors([scale_factor] * 3)
self.transform(S)
def transform(self, transformation):
"""Transform the volume using a :class:`compas.geometry.Transformation`.
Parameters
----------
transformation : :class:`compas.geometry.Transformation`
The transformation to apply on the :class:`BoundingVolume`.
"""
self.volume.transform(transformation)
def __repr__(self):
"""Printable representation of :class:`BoundingVolume`."""
return "BoundingVolume({!r}, {!r})".format(self.type, self.volume)
def copy(self):
"""Make a copy of this :class:`BoundingVolume`.
Returns
-------
:class:`BoundingVolume`
A copy.
"""
cls = type(self)
return cls(self.type, self.volume.copy())
class Constraint(Data):
"""Base class for robot constraints.
Parameters
----------
constraint_type
Constraint type, one of :attr:`Constraint.CONSTRAINT_TYPES`.
weight : :obj:`float`, optional
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to
``1``.
Attributes
----------
constraint_type
Constraint type, one of :attr:`Constraint.CONSTRAINT_TYPES`.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important.
Notes
-----
Constraint.JOINT
Joint constraint type.
Constraint.POSITION
Positional constraint type.
Constraint.ORIENTATION
Orientational constraint type.
Constraint.CONSTRAINT_TYPES
List of possible constraint types.
"""
#: Joint constraint type.
JOINT = 1
#: Positional constraint type.
POSITION = 2
#: Orientational constraint type.
ORIENTATION = 3
#: List of possible constraint types.
CONSTRAINT_TYPES = (JOINT, POSITION, ORIENTATION)
def __init__(self, constraint_type, weight=1.0):
if constraint_type not in self.CONSTRAINT_TYPES:
raise ValueError("Type must be %d, %d or %d" % self.CONSTRAINT_TYPES)
self.type = constraint_type
self.weight = weight
def __data__(self):
return {
"constraint_type": self.type,
"weight": self.weight,
}
def transform(self, transformation):
"""Transform the :class:`Constraint`."""
pass
def scale(self, scale_factor):
"""Scale the :class:`Constraint`."""
pass
def scaled(self, scale_factor):
"""Get a scaled copy of this :class:`Constraint`.
Parameters
----------
scale_factor : :obj:`float`
Scale factor used to scale the :class:`Constraint`.
"""
c = self.copy()
c.scale(scale_factor)
return c
def copy(self):
"""Create a copy of this :class:`Constraint`.
Returns
-------
:class:`BoundingVolume`
"""
cls = type(self)
return cls(self.type, self.weight)
class JointConstraint(Constraint):
"""Constrains the value of a joint to be within a certain bound.
Parameters
----------
joint_name : :obj:`str`
The name of the joint this contraint refers to.
value : :obj:`float`
The targeted value for that joint.
tolerance_above : :obj:`float`
Tolerance above the targeted joint value, in radians. Defaults to ``0``.
tolerance_below : :obj:`float`
Tolerance below the targeted joint value, in radians. Defaults to ``0``.
weight : :obj:`float`, optional
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to
``1``.
Attributes
----------
joint_name : :obj:`str`
The name of the joint this contraint refers to.
value : :obj:`float`
The targeted value for that joint.
tolerance_above : :obj:`float`
Tolerance above the targeted joint value, in radians.
tolerance_below : :obj:`float`
Tolerance below the targeted joint value, in radians.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important.
Examples
--------
>>> from compas_fab.robots import JointConstraint
>>> jc = JointConstraint("joint_0", 1.4, 0.1, 0.1, 1.0)
"""
def __init__(self, joint_name, value, tolerance_above=0.0, tolerance_below=0.0, weight=1.0):
super(JointConstraint, self).__init__(self.JOINT, weight)
self.joint_name = joint_name
self.value = value
self.tolerance_above = abs(tolerance_above)
self.tolerance_below = abs(tolerance_below)
def __data__(self):
return {
"joint_name": self.joint_name,
"value": self.value,
"tolerance_above": self.tolerance_above,
"tolerance_below": self.tolerance_below,
"weight": self.weight,
}
def scale(self, scale_factor):
"""Scale (multiply) the constraint with a factor.
Parameters
----------
scale_factor : :obj:`float`
Factor used to multiply the joint value and tolerance bounds with.
"""
self.value *= scale_factor
self.tolerance_above *= scale_factor
self.tolerance_below *= scale_factor
def __repr__(self):
"""Printable representation of :class:`JointConstraint`."""
return "JointConstraint({!r}, {!r}, {!r}, {!r}, {!r})".format(
self.joint_name, self.value, self.tolerance_above, self.tolerance_below, self.weight
)
def copy(self):
"""Create a copy of this :class:`JointConstraint`.
Returns
-------
:class:`JointConstraint`
"""
cls = type(self)
return cls(self.joint_name, self.value, self.tolerance_above, self.tolerance_below, self.weight)
@classmethod
def joint_constraints_from_configuration(cls, configuration, tolerances_above, tolerances_below):
"""Create joint constraints for all joints of the configuration.
One constraint is created for each joint.
Parameters
----------
configuration: :class:`Configuration`
The target configuration.
tolerances_above: :obj:`list` of :obj:`float`
The tolerances above the targeted configuration's joint value on
each of the joints, defining the upper bound in radians to be
achieved. If only one value is passed in the list, it will be used to create
upper bounds for all joint constraints.
tolerances_below: :obj:`list` of :obj:`float`
The tolerances below the targeted configuration's joint value on
each of the joints, defining the upper bound in radians to be
achieved. If only one value is passed, it will be used to create
lower bounds for all joint constraints.
Returns
-------
:obj:`list` of :class:`JointConstraint`
Raises
------
:exc:`ValueError`
If the passed configuration does not have joint names.
:exc:`ValueError`
If the passed list of tolerance values have a different length than
the configuration.
Notes
-----
Make sure that you are using the correct tolerance units if your robot
has different joint types defined.
"""
joint_names = configuration.joint_names
joint_values = configuration.joint_values
if not joint_names:
raise ValueError("The passed configuration has no joint_names")
if len(joint_names) != len(configuration.joint_values):
raise ValueError(
"The passed configuration has {} joint_names but {} joint_values".format(
len(joint_names), len(joint_values)
)
)
if len(tolerances_above) == 1:
tolerances_above = tolerances_above * len(joint_names)
elif len(tolerances_above) != len(configuration.joint_values):
raise ValueError(
"The number of `tolerances_above` values should either be 1 or equal to the number of joint_values ({}), current number of `tolerances_above` values: {}".format(
len(configuration.joint_values), len(tolerances_above)
)
)
if len(tolerances_below) == 1:
tolerances_below = tolerances_below * len(joint_names)
elif len(tolerances_below) != len(configuration.joint_values):
raise ValueError(
"The number of `tolerances_above` values should either be 1 or equal to the number of joint_values ({}), current number of `tolerances_above` values: {}".format(
len(configuration.joint_values), len(tolerances_below)
)
)
constraints = []
for name, value, tolerance_above, tolerance_below in zip(
joint_names, configuration.joint_values, tolerances_above, tolerances_below
):
constraints.append(JointConstraint(name, value, tolerance_above, tolerance_below))
return constraints
class OrientationConstraint(Constraint):
"""Constrains a link to be within a certain orientation.
Parameters
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
quaternion : :obj:`list` of :obj:`float`
The desired orientation of the link specified by a quaternion in the
order of ``[w, x, y, z]``.
tolerances : :obj:`list` of :obj:`float`, optional
Error tolerances :math:`t_{i}` for each of the frame's axes. If only one
value is passed it will be used for all 3 axes. The respective bound to
be achieved is :math:`(a_{i} - t_{i}, a_{i} + t_{i})`. Defaults to
``[0.01, 0.01, 0.01]``.
weight : :obj:`float`, optional
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to
``1``.
Attributes
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
quaternion : :obj:`list` of :obj:`float`
The desired orientation of the link specified by a quaternion in the
order of ``[w, x, y, z]``.
tolerances : :obj:`list` of :obj:`float`
Error tolerances :math:`t_{i}` for each of the frame's axes. If only one
value is passed it will be used for all 3 axes. The respective bound to
be achieved is :math:`(a_{i} - t_{i}, a_{i} + t_{i})`.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important.
Notes
-----
The rotation tolerance for an axis is defined by the other vector component
values for rotation around corresponding axis.
If you specify the tolerance vector with ``[0.01, 0.01, 6.3]``, it means
that the frame's x-axis and y-axis are allowed to rotate about the z-axis
by an angle of 6.3 radians, whereas the z-axis can only change 0.01.
Examples
--------
>>> from compas.geometry import Frame
>>> from compas_fab.robots import OrientationConstraint
>>> frame = Frame([1, 1, 1], [0.68, 0.68, 0.27], [-0.67, 0.73, -0.15])
>>> oc = OrientationConstraint("link_0", frame.quaternion)
"""
def __init__(self, link_name, quaternion, tolerances=None, weight=1.0):
super(OrientationConstraint, self).__init__(self.ORIENTATION, weight)
self.link_name = link_name
self.quaternion = [float(a) for a in list(quaternion)]
self.tolerances = [float(a) for a in list(tolerances)] if tolerances else [0.01] * 3
def __data__(self):
return {
"link_name": self.link_name,
"quaternion": self.quaternion,
"tolerances": self.tolerances,
"weight": self.weight,
}
def transform(self, transformation):
"""Transform the volume using a :class:`compas.geometry.Transformation`.
Parameters
----------
transformation : :class:`compas.geometry.Transformation`
"""
R = Rotation.from_quaternion(self.quaternion)
R = transformation * R
self.quaternion = R.rotation.quaternion
def __repr__(self):
"""Printable representation of :class:`OrientationConstraint`."""
return "OrientationConstraint({!r}, {!r}, {!r}, {!r})".format(
self.link_name, self.quaternion, self.tolerances, self.weight
)
def copy(self):
"""Create a copy of this :class:`OrientationConstraint`.
Returns
-------
:class:`OrientationConstraint`
"""
cls = type(self)
return cls(self.link_name, self.quaternion[:], self.tolerances[:], self.weight)
@classmethod
def from_frame(cls, frame_WCF, tolerances_orientation, link_name, tool_coordinate_frame=None, weight=1.0):
"""Create an :class:`OrientationConstraint` from a frame on the group's end-effector link.
Only the orientation of the frame is considered for the constraint, expressed
as a quaternion.
Parameters
----------
frame_WCF: :class:`compas.geometry.Frame`
The frame from which we create the orientation constraint.
tolerances_orientation: :obj:`list` of :obj:`float`
Error tolerances :math:`t_{i}` for each of the frame's axes in
radians. If only one value is passed in the list it will be uses for all 3 axes.
link_name : :obj:`str`
The name of the end-effector link. Necessary for creating the position constraint.
tool_coordinate_frame : :class:`compas.geometry.Frame`, optional
The tool tip coordinate frame relative to the flange of the robot.
If not specified, the target frame is relative to the robot's flange.
weight : :obj:`float`, optional
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to
``1``.
Returns
-------
:class:`OrientationConstraint`
Raises
------
:exc:`ValueError`
If tolerance axes given are not one or three values.
Notes
-----
The rotation tolerance for an axis is defined by the other vector
component values for rotation around corresponding axis.
If you specify the tolerances_orientation vector with ``[0.01, 0.01, 6.3]``, it
means that the frame's x-axis and y-axis are allowed to rotate about the
z-axis by an angle of 6.3 radians, whereas the z-axis would only rotate
by 0.01.
Examples
--------
>>> robot = RobotLibrary.ur5()
>>> frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1])
>>> tolerances_orientation = [math.radians(1)] * 3
>>> group = robot.main_group_name
>>> end_effector_link_name = robot.get_end_effector_link_name(group)
>>> OrientationConstraint.from_frame(frame, tolerances_orientation, end_effector_link_name)
OrientationConstraint('tool0', [0.5, 0.5, 0.5, 0.5], [0.017453292519943295, 0.017453292519943295, 0.017453292519943295], 1.0)
"""
if tool_coordinate_frame:
frame_WCF = from_tcf_to_t0cf(frame_WCF, tool_coordinate_frame)
tolerances_orientation = list(tolerances_orientation)
if len(tolerances_orientation) == 1:
tolerances_orientation *= 3
elif len(tolerances_orientation) != 3:
raise ValueError("`tolerances_orientation` must be a list with either 1 or 3 values")
return cls(link_name, frame_WCF.quaternion, tolerances_orientation, weight)
class PositionConstraint(Constraint):
"""Constrains a link to be within a certain bounding volume.
Parameters
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
bounding_volume : :class:`BoundingVolume`
The volume this constraint refers to.
weight : :obj:`float`, optional
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to
``1``.
Attributes
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
bounding_volume : :class:`BoundingVolume`
The volume this constraint refers to.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important.
Examples
--------
>>> from compas.geometry import Sphere
>>> from compas_fab.robots import PositionConstraint
>>> from compas_fab.robots import BoundingVolume
>>> bv = BoundingVolume.from_sphere(Sphere(0.5, point=[3,4,5]))
>>> pc = PositionConstraint('link_0', bv, weight=1.)
"""
def __init__(self, link_name, bounding_volume, weight=1.0):
super(PositionConstraint, self).__init__(self.POSITION, weight)
self.link_name = link_name
self.bounding_volume = bounding_volume
self.weight = weight
def __data__(self):
return {
"link_name": self.link_name,
"bounding_volume": self.bounding_volume,
"weight": self.weight,
}
@classmethod
def from_frame(cls, frame_WCF, tolerance_position, link_name, tool_coordinate_frame=None, weight=1.0):
"""Create a :class:`PositionConstraint` from a frame on the group's end-effector link.
Only the position of the frame is considered for the constraint.
Parameters
----------
frame_WCF : :class:`compas.geometry.Frame`
The frame from which we create position and orientation constraints.
tolerance_position : :obj:`float`
The allowed tolerance to the frame's position (defined in the
robot's units).
link_name : :obj:`str`
The name of the end-effector link. Necessary for creating the position constraint.
tool_coordinate_frame : :class:`compas.geometry.Frame`, optional
The tool tip coordinate frame relative to the flange of the robot.
If not specified, the target frame is relative to the robot's flange.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to ``1``.
Returns
-------
:class:`PositionConstraint`
See Also
--------
:meth:`PositionConstraint.from_box`
:meth:`PositionConstraint.from_mesh`
:meth:`PositionConstraint.from_sphere`
Examples
--------
>>> robot = RobotLibrary.ur5()
>>> frame = Frame([0.4, 0.3, 0.4], [0, 1, 0], [0, 0, 1])
>>> tolerance_position = 0.001
>>> group = robot.main_group_name
>>> end_effector_link_name = robot.get_end_effector_link_name(group)
>>> PositionConstraint.from_frame(frame, tolerance_position, end_effector_link_name) # doctest: +SKIP
PositionConstraint('tool0', BoundingVolume(2, Sphere(Point(0.400, 0.300, 0.400), 0.001)), 1.0) # doctest: +SKIP
"""
if tool_coordinate_frame:
frame_WCF = from_tcf_to_t0cf(frame_WCF, tool_coordinate_frame)
sphere = Sphere(radius=tolerance_position, point=frame_WCF.point)
return cls.from_sphere(link_name, sphere, weight)
@classmethod
def from_box(cls, link_name, box, weight=1.0):
"""Create a :class:`PositionConstraint` from a :class:`compas.geometry.Box`.
Parameters
----------
link_name: :obj:`str`
The name of the link this contraint refers to.
box : :class:`compas.geometry.Box`
Box defining the bounding volume this constraint refers to.
weight : :obj:`float`, optional
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to ``1``.
Returns
-------
:class:`PositionConstraint`
Examples
--------
>>> from compas.geometry import Frame
>>> from compas.geometry import Box
>>> box = Box(4, 4, 4, Frame.worldXY())
>>> pc = PositionConstraint.from_box('link_0', box)
"""
bounding_volume = BoundingVolume.from_box(box)
return cls(link_name, bounding_volume, weight)
@classmethod
def from_sphere(cls, link_name, sphere, weight=1.0):
"""Create a :class:`PositionConstraint` from a :class:`compas.geometry.Sphere`.
Parameters
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
sphere : :class:`compas.geometry.Sphere`
Sphere defining the bounding volume this constraint refers to.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to ``1``.
Returns
-------
:class:`PositionConstraint`
Examples
--------
>>> from compas_fab.robots import PositionConstraint
>>> from compas.geometry import Sphere
>>> sphere = Sphere(radius=0.5, point=[3,4,5])
>>> pc = PositionConstraint.from_sphere('link_0', sphere, weight=1.)
"""
bounding_volume = BoundingVolume.from_sphere(sphere)
return cls(link_name, bounding_volume, weight)
@classmethod
def from_point(cls, link_name, point, tolerance_position, weight=1.0):
"""Create a :class:`PositionConstraint` from a point.
Parameters
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
point : :class:`compas.geometry.Point`
Point defining the bounding volume this constraint refers to.
tolerance_position : :obj:`float`
The allowed tolerance to the point's position (defined in the
robot's units).
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance to
other constraints. Closer to zero means less important. Defaults to ``1``.
Returns
-------
:class:`PositionConstraint`
"""
sphere = Sphere(radius=tolerance_position, point=point)
return cls.from_sphere(link_name, sphere, weight)
@classmethod
def from_mesh(cls, link_name, mesh, weight=1.0):
"""Create a :class:`PositionConstraint` from a :class:`compas.datastructures.Mesh`.
Parameters
----------
link_name : :obj:`str`
The name of the link this contraint refers to.
mesh : :class:`compas.datastructures.Mesh`
Mesh defining the bounding volume this constraint refers to.
weight : :obj:`float`
A weighting factor for this constraint. Denotes relative importance
to other constraints. Closer to zero means less important. Defaults
to ``1``.
Returns
-------
:class:`PositionConstraint`
Examples
--------
>>> from compas.datastructures import Mesh
>>> import compas
>>> mesh = Mesh.from_obj(compas.get('faces.obj'))
>>> pc = PositionConstraint.from_mesh('link_0', mesh)
"""
bounding_volume = BoundingVolume.from_mesh(mesh)
return cls(link_name, bounding_volume, weight)
def scale(self, scale_factor):
"""Scale the :attr:`bounding_volume` uniformely.
Parameters
----------
scale_factor : :obj:`float`
Factor to scale constraining :attr:`bounding_volume`.
"""
self.bounding_volume.scale(scale_factor)
def transform(self, transformation):
"""Transform the :attr:`bounding_volume` using a :class:`compas.geometry.Transformation`.
Parameters
----------
transformation : :class:`compas.geometry.Transformation`
"""
self.bounding_volume.transform(transformation)
def __repr__(self):
"""Printable representation of :class:`PositionConstraint`."""
return "PositionConstraint({!r}, {!r}, {!r})".format(self.link_name, self.bounding_volume, self.weight)
def copy(self):
"""Create a copy of this :class:`PositionConstraint`.
Returns
-------
:class:`PositionConstraint`
"""
cls = type(self)
return cls(self.link_name, self.bounding_volume.copy(), self.weight)