@@ -1871,50 +1871,18 @@ def __init__(
18711871 # connect the links using joint info
18721872 for joint in self ._joints :
18731873 # get references to joint's parent and child
1874- childlink = elinkdict [joint .child ]
1874+ childlink : "rtb.Link" = elinkdict [joint .child ]
18751875 parentlink = elinkdict [joint .parent ]
18761876
18771877 childlink ._parent = parentlink # connect child link to parent
18781878 childlink ._joint_name = joint .name
1879+ # Link precise definition will be done recursively later
1880+ self .elinks = elinks
18791881
1880- # constant part of link transform
1881- trans = SE3 (joint .origin ).t
1882- rot = joint .rpy
1882+ # TODO, why did you put the base_link on the end?
1883+ # easy to do it here
18831884
1884- # childlink.ets will be set later.
1885- # This is because the fully defined parent link is required
1886- # and this loop does not follow the parent-child order.
1887-
1888- # joint limit
1889- try :
1890- if childlink .isjoint :
1891- childlink .qlim = [joint .limit .lower , joint .limit .upper ]
1892- except AttributeError :
1893- # no joint limits provided
1894- pass
1895-
1896- # joint friction
1897- try :
1898- if joint .dynamics .friction is not None :
1899- childlink .B = joint .dynamics .friction
1900-
1901- # TODO Add damping
1902- # joint.dynamics.damping
1903- except AttributeError :
1904- pass
1905-
1906- # joint gear ratio
1907- # TODO, not sure if t.joint.name is a thing
1908- for t in self .transmissions : # pragma nocover
1909- if t .name == joint .name :
1910- childlink .G = t .actuators [0 ].mechanicalReduction
1911-
1912- self .elinks = elinks
1913-
1914- # TODO, why did you put the base_link on the end?
1915- # easy to do it here
1916-
1917- # the childlink.ets will be set in there
1885+ # the childlink.ets and other info is set recursively here
19181886 self ._recursive_axis_definition ()
19191887 return
19201888
@@ -1963,16 +1931,55 @@ def _recursive_axis_definition(
19631931
19641932 ets , from_Rx_to_axis = _find_joint_ets (joint , parent_from_Rx_to_axis )
19651933
1966- for child in self .elinks : # search all link with identical child
1967- is_child = joint .child == child .name
1934+ for childlink in self .elinks : # search all link with identical child
1935+ is_child = joint .child == childlink .name
19681936 if not is_child :
19691937 continue # skips to next link
19701938
1971- child .ets = ets # sets the ets of the joint
1939+ childlink .ets = ets # sets the ets of the joint
1940+ self .finalize_linking (childlink , joint )
1941+
19721942 self ._recursive_axis_definition (
1973- parentname = child .name , parent_from_Rx_to_axis = from_Rx_to_axis
1943+ parentname = childlink .name , parent_from_Rx_to_axis = from_Rx_to_axis
19741944 )
19751945
1946+ def finalize_linking (self , childlink : "rtb.Link" , joint : "Joint" ):
1947+ """
1948+ Finalize the linking process after the link ets is set.
1949+
1950+ This directly changes childlink in place.
1951+ The ets of childlink must be defined prior to this.
1952+
1953+ Attributes
1954+ ----------
1955+ childlink: rtb.Link
1956+ Link to finalize the definition of.
1957+ joint: Joint
1958+ Joint used to define the link.
1959+ """
1960+ try :
1961+ if childlink .isjoint :
1962+ childlink .qlim = [joint .limit .lower , joint .limit .upper ]
1963+ except AttributeError :
1964+ # no joint limits provided
1965+ pass
1966+
1967+ # joint friction
1968+ try :
1969+ if joint .dynamics .friction is not None :
1970+ childlink .B = joint .dynamics .friction
1971+
1972+ # TODO Add damping
1973+ # joint.dynamics.damping
1974+ except AttributeError :
1975+ pass
1976+
1977+ # joint gear ratio
1978+ # TODO, not sure if t.joint.name is a thing
1979+ for t in self .transmissions : # pragma nocover
1980+ if t .name == joint .name :
1981+ childlink .G = t .actuators [0 ].mechanicalReduction
1982+
19761983 @property
19771984 def name (self ):
19781985 """str : The name of the URDF."""
0 commit comments