Joint
This module contains classes for defining joints in a URDF robot model.
Class
- BaseJoint: Abstract base class for joint objects.
- DummyJoint: Represents a dummy joint.
- RevoluteJoint: Represents a revolute joint.
- ContinuousJoint: Represents a continuous joint.
- PrismaticJoint: Represents a prismatic joint.
- FixedJoint: Represents a fixed joint.
- FloatingJoint: Represents a floating joint.
- PlanarJoint: Represents a planar joint.
Dataclass
- JointLimits: Contains the limits for a joint.
- JointMimic: Contains the mimic information for a joint.
- JointDynamics: Contains the dynamics information for a joint.
- Axis: Contains the axis information for a joint.
- Origin: Contains the origin information for a joint.
Enum
- JointType: Enumerates the possible joint types in Onshape (revolute, continuous, prismatic, fixed, floating, planar).
BaseJoint
dataclass
¶
Bases: ABC
Abstract base class for joint objects.
Attributes:
Name | Type | Description |
---|---|---|
name |
str
|
The name of the joint. |
parent |
str
|
The parent link of the joint. |
child |
str
|
The child link of the joint. |
origin |
Origin
|
The origin of the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the joint to an XML element. |
Abstract Properties
joint_type: Returns the type of the joint.
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
to_mjcf(root)
¶
Converts the joint to an XML element and appends it to the given root element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Element
|
The root element to append the joint to. |
required |
Source code in onshape_robotics_toolkit\models\joint.py
302 303 304 305 306 307 308 309 310 311 |
|
to_xml(root=None)
¶
Convert the joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the joint. |
Source code in onshape_robotics_toolkit\models\joint.py
283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 |
|
ContinuousJoint
dataclass
¶
Bases: BaseJoint
Represents a continuous joint.
Attributes:
Name | Type | Description |
---|---|---|
mimic |
JointMimic
|
The mimic information for the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the continuous joint to an XML element. |
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = ContinuousJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "continuous". |
from_xml(element)
classmethod
¶
Create a continuous joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the continuous joint from. |
required |
Returns:
Type | Description |
---|---|
ContinuousJoint
|
The continuous joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "continuous")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> mimic = ET.SubElement(element, "mimic", joint="joint1", multiplier="1.0", offset="0.0")
>>> ContinuousJoint.from_xml(element)
ContinuousJoint( name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0)), mimic=JointMimic(joint="joint1", multiplier=1.0, offset=0.0) )
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
to_xml(root=None)
¶
Convert the continuous joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the continuous joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the continuous joint. |
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = ContinuousJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
DummyJoint
dataclass
¶
Bases: BaseJoint
Represents a dummy joint.
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> joint = DummyJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... )
>>> joint.joint_type
'dummy'
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "dummy". |
from_xml(element)
classmethod
¶
Create a dummy joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the dummy joint from. |
required |
Returns:
Type | Description |
---|---|
DummyJoint
|
The dummy joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "dummy")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> DummyJoint.from_xml(element)
DummyJoint(name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0)))
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
FixedJoint
dataclass
¶
Bases: BaseJoint
Represents a fixed joint.
Methods:
Name | Description |
---|---|
to_xml |
Converts the fixed joint to an XML element. |
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> joint = FixedJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "fixed". |
from_xml(element)
classmethod
¶
Create a fixed joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the fixed joint from. |
required |
Returns:
Type | Description |
---|---|
FixedJoint
|
The fixed joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "fixed")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> FixedJoint.from_xml(element)
FixedJoint(name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
to_xml(root=None)
¶
Convert the fixed joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the fixed joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the fixed joint. |
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> joint = FixedJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 |
|
FloatingJoint
dataclass
¶
Bases: BaseJoint
Represents a floating joint.
Attributes:
Name | Type | Description |
---|---|---|
mimic |
JointMimic
|
The mimic information for the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the floating joint to an XML element. |
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = FloatingJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "floating". |
from_xml(element)
classmethod
¶
Create a floating joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the floating joint from. |
required |
Returns:
Type | Description |
---|---|
FloatingJoint
|
The floating joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "floating")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> mimic = ET.SubElement(element, "mimic", joint="joint1", multiplier="1.0", offset="0.0")
>>> FloatingJoint.from_xml(element)
FloatingJoint( name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0)), mimic=JointMimic(joint="joint1", multiplier=1.0, offset=0.0) )
Source code in onshape_robotics_toolkit\models\joint.py
995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 |
|
to_xml(root=None)
¶
Convert the floating joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the floating joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the floating joint. |
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = FloatingJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
JointDynamics
dataclass
¶
Represents the dynamics information for a joint.
Attributes:
Name | Type | Description |
---|---|---|
damping |
float
|
The damping coefficient of the joint. |
friction |
float
|
The friction coefficient of the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the dynamics information to an XML element. |
Examples:
>>> dynamics = JointDynamics(damping=0.0, friction=0.0)
>>> dynamics.to_xml()
<Element 'dynamics' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
from_xml(element)
¶
Create joint dynamics from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the joint dynamics from. |
required |
Returns:
Type | Description |
---|---|
JointDynamics
|
The joint dynamics created from the XML element. |
Examples:
>>> element = ET.Element("dynamics")
>>> element.set("damping", "0.0")
>>> element.set("friction", "0.0")
>>> JointDynamics.from_xml(element)
JointDynamics(damping=0.0, friction=0.0)
Source code in onshape_robotics_toolkit\models\joint.py
237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 |
|
to_xml(root=None)
¶
Convert the dynamics information to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the dynamics information to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the dynamics information. |
Examples:
>>> dynamics = JointDynamics(damping=0.0, friction=0.0)
>>> dynamics.to_xml()
<Element 'dynamics' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 |
|
JointLimits
dataclass
¶
Represents the limits of a joint.
Attributes:
Name | Type | Description |
---|---|---|
effort |
float
|
The effort limit of the joint. |
velocity |
float
|
The velocity limit of the joint. |
lower |
float
|
The lower limit of the joint. |
upper |
float
|
The upper limit of the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the joint limits to an XML element. |
Examples:
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> limits.to_xml()
<Element 'limit' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
to_xml(root=None)
¶
Convert the joint limits to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the joint limits to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the joint limits. |
Examples:
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> limits.to_xml()
<Element 'limit' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 |
|
JointMimic
dataclass
¶
Represents the mimic information for a joint.
Attributes:
Name | Type | Description |
---|---|---|
joint |
str
|
The joint to mimic. |
multiplier |
float
|
The multiplier for the mimic. |
offset |
float
|
The offset for the mimic. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the mimic information to an XML element. |
Examples:
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> mimic.to_xml()
<Element 'mimic' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
from_xml(element)
classmethod
¶
Create a joint mimic from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the joint mimic from. |
required |
Returns:
Type | Description |
---|---|
JointMimic
|
The joint mimic created from the XML element. |
Examples:
>>> element = ET.Element("mimic")
>>> element.set("joint", "joint1")
>>> element.set("multiplier", "1.0")
>>> element.set("offset", "0.0")
>>> JointMimic.from_xml(element)
JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
Source code in onshape_robotics_toolkit\models\joint.py
169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 |
|
to_xml(root=None)
¶
Convert the mimic information to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the mimic information to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the mimic information. |
Examples:
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> mimic.to_xml()
<Element 'mimic' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 |
|
JointType
¶
Bases: str
, Enum
Enumerates the possible joint types in Onshape
Attributes:
Name | Type | Description |
---|---|---|
REVOLUTE |
str
|
Revolute joint |
CONTINUOUS |
str
|
Continuous joint |
PRISMATIC |
str
|
Prismatic joint |
FIXED |
str
|
Fixed joint |
FLOATING |
str
|
Floating joint |
PLANAR |
str
|
Planar joint |
Examples:
>>> JointType.REVOLUTE
'revolute'
>>> JointType.CONTINUOUS
'continuous'
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
PlanarJoint
dataclass
¶
Bases: BaseJoint
Represents a planar joint.
Attributes:
Name | Type | Description |
---|---|---|
limits |
JointLimits
|
The limits of the joint. |
axis |
Axis
|
The axis of the joint. |
mimic |
JointMimic
|
The mimic information for the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the planar joint to an XML element. |
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> axis = Axis(xyz=(0, 0, 1))
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = PlanarJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... limits=limits,
... axis=axis,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "planar". |
from_xml(element)
classmethod
¶
Create a planar joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the planar joint from. |
required |
Returns:
Type | Description |
---|---|
PlanarJoint
|
The planar joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "planar")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> limits = ET.SubElement(element, "limit", effort="10.0", velocity="1.0", lower="-1.0", upper="1.0")
>>> axis = ET.SubElement(element, "axis", xyz="0 0 1")
>>> mimic = ET.SubElement(element, "mimic", joint="joint1", multiplier="1.0", offset="0.0")
>>> PlanarJoint.from_xml(element)
PlanarJoint( name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0)), limits=JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0), axis=Axis(xyz=(0, 0, 1)), mimic=JointMimic(joint="joint1", multiplier=1.0, offset=0.0) )
Source code in onshape_robotics_toolkit\models\joint.py
1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152 1153 1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 |
|
to_xml(root=None)
¶
Convert the planar joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the planar joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the planar joint. |
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> axis = Axis(xyz=(0, 0, 1))
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = PlanarJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... limits=limits,
... axis=axis,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113 1114 1115 1116 1117 1118 1119 1120 |
|
PrismaticJoint
dataclass
¶
Bases: BaseJoint
Represents a prismatic joint.
Attributes:
Name | Type | Description |
---|---|---|
limits |
JointLimits
|
The limits of the joint. |
axis |
Axis
|
The axis of the joint. |
dynamics |
JointDynamics
|
The dynamics of the joint. |
mimic |
JointMimic
|
The mimic information for the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the prismatic joint to an XML element. |
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> axis = Axis(xyz=(0, 0, 1))
>>> dynamics = JointDynamics(damping=0.0, friction=0.0)
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = PrismaticJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... limits=limits,
... axis=axis,
... dynamics=dynamics,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "prismatic". |
from_xml(element)
classmethod
¶
Create a prismatic joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the prismatic joint from. |
required |
Returns:
Type | Description |
---|---|
PrismaticJoint
|
The prismatic joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "prismatic")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> limits = ET.SubElement(element, "limit", effort="10.0", velocity="1.0", lower="-1.0", upper="1.0")
>>> axis = ET.SubElement(element, "axis", xyz="0 0 1")
>>> dynamics = ET.SubElement(element, "dynamics", damping="0.0", friction="0.0")
>>> mimic = ET.SubElement(element, "mimic", joint="joint1", multiplier="1.0", offset="0.0")
>>> PrismaticJoint.from_xml(element)
PrismaticJoint( name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0)), limits=JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0), axis=Axis(xyz=(0, 0, 1)), dynamics=JointDynamics(damping=0.0, friction=0.0), mimic=JointMimic(joint="joint1", multiplier=1.0, offset=0.0) )
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
to_xml(root=None)
¶
Convert the prismatic joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the prismatic joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the prismatic joint |
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> axis = Axis(xyz=(0, 0, 1))
>>> dynamics = JointDynamics(damping=0.0, friction=0.0)
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = PrismaticJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... limits=limits,
... axis=axis,
... dynamics=dynamics,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
RevoluteJoint
dataclass
¶
Bases: BaseJoint
Represents a revolute joint.
Attributes:
Name | Type | Description |
---|---|---|
limits |
JointLimits
|
The limits of the joint. |
axis |
Axis
|
The axis of the joint. |
dynamics |
JointDynamics
|
The dynamics of the joint. |
mimic |
JointMimic
|
The mimic information for the joint. |
Methods:
Name | Description |
---|---|
to_xml |
Converts the revolute joint to an XML element. |
Properties
joint_type: The type of the joint.
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> axis = Axis(xyz=(0, 0, 1))
>>> dynamics = JointDynamics(damping=0.0, friction=0.0)
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = RevoluteJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... limits=limits,
... axis=axis,
... dynamics=dynamics,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
joint_type: str
property
¶
The type of the joint.
Returns:
Type | Description |
---|---|
str
|
The type of the joint: "revolute". |
from_xml(element)
classmethod
¶
Create a revolute joint from an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
element
|
Element
|
The XML element to create the revolute joint from. |
required |
Returns:
Type | Description |
---|---|
RevoluteJoint
|
The revolute joint created from the XML element. |
Examples:
>>> element = ET.Element("joint")
>>> element.set("name", "joint1")
>>> element.set("type", "revolute")
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> ET.SubElement(element, "origin", xyz="0 0 0", rpy="0 0 0")
>>> ET.SubElement(element, "parent", link="base_link")
>>> ET.SubElement(element, "child", link="link1")
>>> limits = ET.SubElement(element, "limit", effort="10.0", velocity="1.0", lower="-1.0", upper="1.0")
>>> axis = ET.SubElement(element, "axis", xyz="0 0 1")
>>> dynamics = ET.SubElement(element, "dynamics", damping="0.0", friction="0.0")
>>> mimic = ET.SubElement(element, "mimic", joint="joint1", multiplier="1.0", offset="0.0")
>>> RevoluteJoint.from_xml(element)
RevoluteJoint( name="joint1", parent="base_link", child="link1", origin=Origin(xyz=(0, 0, 0), rpy=(0, 0, 0)), limits=JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0), axis=Axis(xyz=(0, 0, 1)), dynamics=JointDynamics(damping=0.0, friction=0.0), mimic=JointMimic(joint="joint1", multiplier=1.0, offset=0.0) )
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|
to_mjcf(root)
¶
Converts the revolute joint to an XML element and appends it to the given root element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Element
|
The root element to append the revolute joint to. |
required |
Source code in onshape_robotics_toolkit\models\joint.py
465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 |
|
to_xml(root=None)
¶
Convert the revolute joint to an XML element.
Parameters:
Name | Type | Description | Default |
---|---|---|---|
root
|
Optional[Element]
|
The root element to append the revolute joint to. |
None
|
Returns:
Type | Description |
---|---|
Element
|
The XML element representing the revolute joint. |
Examples:
>>> origin = Origin(xyz=(0, 0, 0), rpy=(0, 0, 0))
>>> limits = JointLimits(effort=10.0, velocity=1.0, lower=-1.0, upper=1.0)
>>> axis = Axis(xyz=(0, 0, 1))
>>> dynamics = JointDynamics(damping=0.0, friction=0.0)
>>> mimic = JointMimic(joint="joint1", multiplier=1.0, offset=0.0)
>>> joint = RevoluteJoint(
... name="joint1",
... parent="base_link",
... child="link1",
... origin=origin,
... limits=limits,
... axis=axis,
... dynamics=dynamics,
... mimic=mimic,
... )
>>> joint.to_xml()
<Element 'joint' at 0x7f8b3c0b4c70>
Source code in onshape_robotics_toolkit\models\joint.py
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 |
|