-
Notifications
You must be signed in to change notification settings - Fork 474
/
urdf.py
1973 lines (1676 loc) · 58.5 KB
/
urdf.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
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#!/usr/bin/env python
"""
@author (Original) Matthew Matl, Github: mmatl
@author (Adapted by) Jesse Haviland
"""
import numpy as np
import roboticstoolbox as rtb
import spatialgeometry as gm
import copy
import os
import xml.etree.ElementTree as ETT
from spatialmath import SE3
from spatialmath.base import unitvec_norm, angvec2r, tr2rpy
from io import BytesIO
from roboticstoolbox.tools.data import rtb_path_to_datafile
from pathlib import PurePosixPath
from .utils import parse_origin, configure_origin
# Global variable for the base path of the robot meshes
_base_path = None
class URDFType(object):
"""Abstract base class for all URDF types.
This has useful class methods for automatic parsing/unparsing
of XML trees.
There are three overridable class variables:
- ``_ATTRIBS`` - This is a dictionary mapping attribute names to a tuple,
``(type, required)`` where ``type`` is the Python type for the
attribute and ``required`` is a boolean stating whether the attribute
is required to be present.
- ``_ELEMENTS`` - This is a dictionary mapping element names to a tuple,
``(type, required, multiple)`` where ``type`` is the Python type for the
element, ``required`` is a boolean stating whether the element
is required to be present, and ``multiple`` is a boolean indicating
whether multiple elements of this type could be present.
Elements are child nodes in the XML tree, and their type must be a
subclass of :class:`.URDFType`.
- ``_TAG`` - This is a string that represents the XML tag for the node
containing this type of object.
"""
_ATTRIBS = {} # Map from attrib name to (type, required)
_ELEMENTS = {} # Map from element name to (type, required, multiple)
_TAG = "" # XML tag for this element
def __init__(self): # pragma nocover
pass
@classmethod
def _parse_attrib(cls, val_type, val):
"""Parse an XML attribute into a python value.
Parameters
----------
val_type : :class:`type`
The type of value to create.
val : :class:`object`
The value to parse.
Returns
-------
val : :class:`object`
The parsed attribute.
"""
if val_type == np.ndarray:
val = np.fromstring(val, sep=" ")
else:
val = val_type(val)
return val
@classmethod
def _parse_simple_attribs(cls, node):
"""Parse all attributes in the _ATTRIBS array for this class.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse attributes for.
Returns
-------
kwargs : dict
Map from attribute name to value. If the attribute is not
required and is not present, that attribute's name will map to
``None``.
"""
kwargs = {}
for a in cls._ATTRIBS:
t, r = cls._ATTRIBS[a] # t = type, r = required (bool)
if r:
try:
v = cls._parse_attrib(t, node.attrib[a])
except Exception: # pragma nocover
raise ValueError(
"Missing required attribute {} when parsing an object "
"of type {}".format(a, cls.__name__)
)
else:
v = None
if a in node.attrib:
v = cls._parse_attrib(t, node.attrib[a])
kwargs[a] = v
return kwargs
@classmethod
def _parse_simple_elements(cls, node, path):
"""Parse all elements in the _ELEMENTS array from the children of
this node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse children for.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
Returns
-------
kwargs : dict
Map from element names to the :class:`URDFType` subclass (or list,
if ``multiple`` was set) created for that element.
"""
kwargs = {}
for a in cls._ELEMENTS:
t, r, m = cls._ELEMENTS[a]
if not m:
v = node.find(t._TAG)
if r or v is not None:
v = t._from_xml(v, path)
else:
vs = node.findall(t._TAG)
if len(vs) == 0 and r: # pragma nocover
raise ValueError(
"Missing required subelement(s) of type {} when "
"parsing an object of type {}".format(t.__name__, cls.__name__)
)
v = [t._from_xml(n, path) for n in vs]
kwargs[a] = v
return kwargs
@classmethod
def _parse(cls, node, path):
"""Parse all elements and attributes in the _ELEMENTS and _ATTRIBS
arrays for a node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
Returns
-------
kwargs : dict
Map from names to Python classes created from the attributes
and elements in the class arrays.
"""
kwargs = cls._parse_simple_attribs(node)
kwargs.update(cls._parse_simple_elements(node, path))
return kwargs
@classmethod
def _from_xml(cls, node, path):
"""Create an instance of this class from an XML node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
Returns
-------
obj : :class:`URDFType`
An instance of this class parsed from the node.
"""
return cls(**cls._parse(node, path))
###############################################################################
# Link types
###############################################################################
class Box(URDFType):
"""A rectangular prism whose center is at the local origin.
Parameters
----------
size : (3,) float
The length, width, and height of the box in meters.
"""
_ATTRIBS = {"size": (np.ndarray, True)}
_TAG = "box"
def __init__(self, size):
self.size = size
@property
def size(self):
"""(3,) float : The length, width, and height of the box in meters."""
return self._size
@size.setter
def size(self, value):
self._size = np.asanyarray(value).astype(np.float64)
class Cylinder(URDFType):
"""A cylinder whose center is at the local origin.
Parameters
----------
radius : float
The radius of the cylinder in meters.
length : float
The length of the cylinder in meters.
"""
_ATTRIBS = {
"radius": (float, True),
"length": (float, True),
}
_TAG = "cylinder"
def __init__(self, radius, length):
self.radius = radius
self.length = length
@property
def radius(self):
"""float : The radius of the cylinder in meters."""
return self._radius
@radius.setter
def radius(self, value):
self._radius = float(value)
@property
def length(self):
"""float : The length of the cylinder in meters."""
return self._length
@length.setter
def length(self, value):
self._length = float(value)
class Sphere(URDFType):
"""A sphere whose center is at the local origin.
Parameters
----------
radius : float
The radius of the sphere in meters.
"""
_ATTRIBS = {
"radius": (float, True),
}
_TAG = "sphere"
def __init__(self, radius):
self.radius = radius
@property
def radius(self):
"""float : The radius of the sphere in meters."""
return self._radius
@radius.setter
def radius(self, value):
self._radius = float(value)
class Mesh(URDFType):
"""A triangular mesh object.
Parameters
----------
filename : str
The path to the mesh that contains this object. This can be
relative to the top-level URDF or an absolute path.
scale : (3,) float, optional
The scaling value for the mesh along the XYZ axes.
If ``None``, assumes no scale is applied.
"""
_ATTRIBS = {"filename": (str, True), "scale": (np.ndarray, False)}
_TAG = "mesh"
def __init__(self, filename, scale=None):
self.filename = filename
self.scale = scale
@property
def filename(self):
"""str : The path to the mesh file for this object."""
return self._filename
@filename.setter
def filename(self, value):
global _base_path
if value.startswith("package://"):
value = value.replace("package://", "")
if _base_path is None:
value = rtb_path_to_datafile("xacro", value)
else:
value = _base_path / PurePosixPath(value)
self._filename = str(value)
@property
def scale(self):
"""(3,) float : A scaling for the mesh along its local XYZ axes."""
return self._scale
@scale.setter
def scale(self, value):
if value is not None:
value = np.asanyarray(value).astype(np.float64)
self._scale = value
@classmethod
def _from_xml(cls, node, path):
kwargs = cls._parse(node, path)
return Mesh(**kwargs)
class Material(URDFType):
"""A material for some geometry.
Parameters
----------
name : str
The name of the material.
color : (4,) float, optional
The RGBA color of the material in the range [0,1].
texture : :class:`.Texture`, optional
A texture for the material.
"""
_ATTRIBS = {"name": (str, True)}
_ELEMENTS = {}
_TAG = "material"
def __init__(self, name, color=None, texture=None):
# if color is None:
# color = name
self.name = name
self.color = color
self.texture = texture
@classmethod
def _from_xml(cls, node, path): # pragma nocover
kwargs = cls._parse(node, path)
# Extract the color -- it's weirdly an attribute of a subelement
color = node.find("color")
if color is not None:
color = np.fromstring(color.attrib["rgba"], sep=" ", dtype=np.float64)
kwargs["color"] = color
return Material(**kwargs)
class Geometry(URDFType):
"""A wrapper for all geometry types.
Only one of the following values can be set, all others should be set
to ``None``.
Parameters
----------
box : :class:`.Box`, optional
Box geometry.
cylinder : :class:`.Cylinder`
Cylindrical geometry.
sphere : :class:`.Sphere`
Spherical geometry.
mesh : :class:`.Mesh`
Mesh geometry.
"""
_ELEMENTS = {
"box": (Box, False, False),
"cylinder": (Cylinder, False, False),
"sphere": (Sphere, False, False),
"mesh": (Mesh, False, False),
}
_TAG = "geometry"
def __init__(self, box=None, cylinder=None, sphere=None, mesh=None):
if (
box is None and cylinder is None and sphere is None and mesh is None
): # pragma nocover
raise ValueError("At least one geometry element must be set")
if box is not None:
self.box = box
self.ob = gm.Cuboid(box.size)
if cylinder is not None:
self.cylinder = cylinder
self.ob = gm.Cylinder(cylinder.radius, cylinder.length)
if sphere is not None:
self.sphere = sphere
self.ob = gm.Sphere(sphere.radius)
if mesh is not None:
self.mesh = mesh
self.ob = gm.Mesh(mesh.filename, scale=mesh.scale)
@property
def box(self):
""":class:`.Box` : Box geometry."""
return self._box
@box.setter
def box(self, value):
if value is not None and not isinstance(value, Box): # pragma nocover
raise TypeError("Expected Box type")
self._box = value
@property
def cylinder(self):
""":class:`.Cylinder` : Cylinder geometry."""
return self._cylinder
@cylinder.setter
def cylinder(self, value):
if value is not None and not isinstance(value, Cylinder):
raise TypeError("Expected Cylinder type") # pragma nocover
self._cylinder = value
@property
def sphere(self):
""":class:`.Sphere` : Spherical geometry."""
return self._sphere
@sphere.setter
def sphere(self, value):
if value is not None and not isinstance(value, Sphere):
raise TypeError("Expected Sphere type") # pragma nocover
self._sphere = value
@property
def mesh(self):
""":class:`.Mesh` : Mesh geometry."""
return self._mesh
@mesh.setter
def mesh(self, value):
if value is not None and not isinstance(value, Mesh):
raise TypeError("Expected Mesh type") # pragma nocover
self._mesh = value
@property
def geometry(self): # pragma nocover
""":class:`.Box`, :class:`.Cylinder`, :class:`.Sphere`, or
:class:`.Mesh` : The valid geometry element.
"""
if self.box is not None:
return self.box
if self.cylinder is not None:
return self.cylinder
if self.sphere is not None:
return self.sphere
if self.mesh is not None:
return self.mesh
return None
class Collision(URDFType):
"""Collision properties of a link.
Parameters
----------
geometry : :class:`.Geometry`
The geometry of the element
name : str, optional
The name of the collision geometry.
origin : (4,4) float, optional
The pose of the collision element relative to the link frame.
Defaults to identity.
"""
_ATTRIBS = {"name": (str, False)}
_ELEMENTS = {
"geometry": (Geometry, True, False),
}
_TAG = "collision"
def __init__(self, name, origin, geometry):
self.geometry = geometry
self.name = name
self.origin = origin
self.geometry.ob.T = origin
@property
def geometry(self):
""":class:`.Geometry` : The geometry of this element."""
return self._geometry
@geometry.setter
def geometry(self, value):
if not isinstance(value, Geometry): # pragma nocover
raise TypeError("Must set geometry with Geometry object")
self._geometry = value
@property
def name(self):
"""str : The name of this collision element."""
return self._name
@name.setter
def name(self, value):
if value is not None:
value = str(value)
self._name = value
@property
def origin(self):
"""(4,4) float : The pose of this element relative to the link frame."""
return self._origin
@origin.setter
def origin(self, value):
self._origin = configure_origin(value)
@classmethod
def _from_xml(cls, node, path):
kwargs = cls._parse(node, path)
kwargs["origin"], _ = parse_origin(node)
return Collision(**kwargs)
class Visual(URDFType):
"""Visual properties of a link.
Parameters
----------
geometry : :class:`.Geometry`
The geometry of the element
name : str, optional
The name of the visual geometry.
origin : (4,4) float, optional
The pose of the visual element relative to the link frame.
Defaults to identity.
material : :class:`.Material`, optional
The material of the element.
"""
_ATTRIBS = {"name": (str, False)}
_ELEMENTS = {
"geometry": (Geometry, True, False),
"material": (Material, False, False),
}
_TAG = "visual"
def __init__(self, geometry, name=None, origin=None, material=None):
self.geometry = geometry
geometry.ob.T = origin
self.name = name
self.origin = origin
self.material = material
# Do not set material color yet. The top level URDF colors have not
# been parsed/defined yet so we do not know what 'Grey' or 'Blue2'
# mean yet. We set colors after these top level definitions come in
# Do set it if the color was defined in line by the URDF
if material is not None and material.color is not None:
self.geometry.ob.color = material.color
@property
def geometry(self):
""":class:`.Geometry` : The geometry of this element."""
return self._geometry
@geometry.setter
def geometry(self, value):
if not isinstance(value, Geometry): # pragma nocover
raise TypeError("Must set geometry with Geometry object")
self._geometry = value
@property
def name(self):
"""str : The name of this visual element."""
return self._name
@name.setter
def name(self, value):
if value is not None:
value = str(value)
self._name = value
@property
def origin(self):
"""(4,4) float : The pose of this element relative to the link frame."""
return self._origin
@origin.setter
def origin(self, value):
self._origin = configure_origin(value)
@classmethod
def _from_xml(cls, node, path):
kwargs = cls._parse(node, path)
kwargs["origin"], _ = parse_origin(node)
return Visual(**kwargs)
class Inertial(URDFType):
"""The inertial properties of a link.
Parameters
----------
mass : float
The mass of the link in kilograms.
inertia : (3,3) float
The 3x3 symmetric rotational inertia matrix.
origin : (4,4) float, optional
The pose of the inertials relative to the link frame.
Defaults to identity if not specified.
"""
_TAG = "inertial"
def __init__(self, mass=None, inertia=None, origin=None):
self._mass = mass
self._inertia = inertia
self._origin = origin
@property
def mass(self):
"""float : The mass of the link in kilograms."""
return self._mass
@mass.setter
def mass(self, value):
self._mass = float(value)
@property
def inertia(self):
"""(3,3) float : The 3x3 symmetric rotational inertia matrix."""
return self._inertia
@inertia.setter
def inertia(self, value):
value = np.asanyarray(value).astype(np.float64)
if not np.allclose(value, value.T): # pragma nocover
raise ValueError("Inertia must be a symmetric matrix")
self._inertia = value
@property
def origin(self):
"""(4,4) float : The pose of the inertials relative to the link frame."""
return self._origin
@origin.setter
def origin(self, value):
self._origin = configure_origin(value)
@classmethod
def _from_xml(cls, node, path):
origin, _ = parse_origin(node)
mass = float(node.find("mass").attrib["value"])
n = node.find("inertia")
xx = float(n.attrib["ixx"])
xy = float(n.attrib["ixy"])
xz = float(n.attrib["ixz"])
yy = float(n.attrib["iyy"])
yz = float(n.attrib["iyz"])
zz = float(n.attrib["izz"])
inertia = np.array([[xx, xy, xz], [xy, yy, yz], [xz, yz, zz]], dtype=np.float64)
return Inertial(mass=mass, inertia=inertia, origin=origin)
###############################################################################
# Joint types
###############################################################################
class JointCalibration(URDFType): # pragma nocover
"""The reference positions of the joint.
Parameters
----------
rising : float, optional
When the joint moves in a positive direction, this position will
trigger a rising edge.
falling :
When the joint moves in a positive direction, this position will
trigger a falling edge.
"""
_ATTRIBS = {"rising": (float, False), "falling": (float, False)}
_TAG = "calibration"
def __init__(self, rising=None, falling=None):
self.rising = rising
self.falling = falling
@property
def rising(self):
"""float : description."""
return self._rising
@rising.setter
def rising(self, value):
if value is not None:
value = float(value)
self._rising = value
@property
def falling(self):
"""float : description."""
return self._falling
@falling.setter
def falling(self, value):
if value is not None:
value = float(value)
self._falling = value
def copy(self, prefix="", scale=None):
"""Create a deep copy of the visual with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all joint and link names.
Returns
-------
:class:`.JointCalibration`
A deep copy of the visual.
"""
return JointCalibration(
rising=self.rising,
falling=self.falling,
)
class JointDynamics(URDFType):
"""The dynamic properties of the joint.
Parameters
----------
damping : float
The damping value of the joint (Ns/m for prismatic joints,
Nms/rad for revolute).
friction : float
The static friction value of the joint (N for prismatic joints,
Nm for revolute).
"""
_ATTRIBS = {
"damping": (float, False),
"friction": (float, False),
}
_TAG = "dynamics"
def __init__(self, damping, friction):
self.damping = damping
self.friction = friction
@property
def damping(self): # pragma nocover
"""float : The damping value of the joint."""
return self._damping
@damping.setter
def damping(self, value):
if value is not None:
value = float(value)
self._damping = value
@property
def friction(self):
"""float : The static friction value of the joint."""
return self._friction
@friction.setter
def friction(self, value):
if value is not None:
value = float(value)
self._friction = value
class JointLimit(URDFType):
"""The limits of the joint.
Parameters
----------
effort : float
The maximum joint effort (N for prismatic joints, Nm for revolute).
velocity : float
The maximum joint velocity (m/s for prismatic joints, rad/s for
revolute).
lower : float, optional
The lower joint limit (m for prismatic joints, rad for revolute).
upper : float, optional
The upper joint limit (m for prismatic joints, rad for revolute).
"""
_ATTRIBS = {
"effort": (float, True),
"velocity": (float, True),
"lower": (float, False),
"upper": (float, False),
}
_TAG = "limit"
def __init__(self, effort, velocity, lower=None, upper=None):
self.effort = effort
self.velocity = velocity
self.lower = lower
self.upper = upper
@property
def effort(self):
"""float : The maximum joint effort."""
return self._effort
@effort.setter
def effort(self, value):
self._effort = float(value)
@property
def velocity(self):
"""float : The maximum joint velocity."""
return self._velocity
@velocity.setter
def velocity(self, value):
self._velocity = float(value)
@property
def lower(self):
"""float : The lower joint limit."""
return self._lower
@lower.setter
def lower(self, value):
if value is not None:
value = float(value)
self._lower = value
@property
def upper(self):
"""float : The upper joint limit."""
return self._upper
@upper.setter
def upper(self, value):
if value is not None:
value = float(value)
self._upper = value
class JointMimic(URDFType): # pragma nocover
"""A mimicry tag for a joint, which forces its configuration to
mimic another joint's.
This joint's configuration value is set equal to
``multiplier * other_joint_cfg + offset``.
Parameters
----------
joint : str
The name of the joint to mimic.
multiplier : float
The joint configuration multiplier. Defaults to 1.0.
offset : float, optional
The joint configuration offset. Defaults to 0.0.
"""
_ATTRIBS = {
"joint": (str, True),
"multiplier": (float, False),
"offset": (float, False),
}
_TAG = "mimic"
def __init__(self, joint, multiplier=None, offset=None):
self.joint = joint
self.multiplier = multiplier
self.offset = offset
@property
def joint(self):
"""float : The name of the joint to mimic."""
return self._joint
@joint.setter
def joint(self, value):
self._joint = str(value)
@property
def multiplier(self):
"""float : The multiplier for the joint configuration."""
return self._multiplier
@multiplier.setter
def multiplier(self, value):
if value is not None:
value = float(value)
else:
value = 1.0
self._multiplier = value
@property
def offset(self):
"""float : The offset for the joint configuration"""
return self._offset
@offset.setter
def offset(self, value):
if value is not None:
value = float(value)
else:
value = 0.0
self._offset = value
class SafetyController(URDFType): # pragma nocover
"""A controller for joint movement safety.
Parameters
----------
k_velocity : float
An attribute specifying the relation between the effort and velocity
limits.
k_position : float, optional
An attribute specifying the relation between the position and velocity
limits. Defaults to 0.0.
soft_lower_limit : float, optional
The lower joint boundary where the safety controller kicks in.
Defaults to 0.0.
soft_upper_limit : float, optional
The upper joint boundary where the safety controller kicks in.
Defaults to 0.0.
"""
_ATTRIBS = {
"k_velocity": (float, True),
"k_position": (float, False),
"soft_lower_limit": (float, False),
"soft_upper_limit": (float, False),
}
_TAG = "safety_controller"
def __init__(
self, k_velocity, k_position=None, soft_lower_limit=None, soft_upper_limit=None
):
self.k_velocity = k_velocity
self.k_position = k_position
self.soft_lower_limit = soft_lower_limit
self.soft_upper_limit = soft_upper_limit
@property
def soft_lower_limit(self):
"""float : The soft lower limit where the safety controller kicks in."""
return self._soft_lower_limit
@soft_lower_limit.setter
def soft_lower_limit(self, value):
if value is not None:
value = float(value)
else:
value = 0.0
self._soft_lower_limit = value
@property
def soft_upper_limit(self):
"""float : The soft upper limit where the safety controller kicks in."""
return self._soft_upper_limit
@soft_upper_limit.setter
def soft_upper_limit(self, value):
if value is not None:
value = float(value)
else:
value = 0.0
self._soft_upper_limit = value
@property
def k_position(self):
"""float : A relation between the position and velocity limits."""
return self._k_position
@k_position.setter
def k_position(self, value):
if value is not None:
value = float(value)
else:
value = 0.0
self._k_position = value
@property
def k_velocity(self):
"""float : A relation between the effort and velocity limits."""
return self._k_velocity
@k_velocity.setter
def k_velocity(self, value):
self._k_velocity = float(value)
###############################################################################