@@ -1821,7 +1821,7 @@ def joint_velocity_damper(self, ps=0.05, pi=0.1, n=None, gain=1.0):
1821
1821
1822
1822
def link_collision_damper (
1823
1823
self , shape , q = None , di = 0.3 , ds = 0.05 , xi = 1.0 ,
1824
- from_link = None , to_link = None ):
1824
+ endlink = None , startlink = None ):
1825
1825
'''
1826
1826
Formulates an inequality contraint which, when optimised for will
1827
1827
make it impossible for the robot to run into a collision. Requires
@@ -1847,13 +1847,13 @@ def link_collision_damper(
1847
1847
:rtype: ndarray(6), ndarray(6)
1848
1848
'''
1849
1849
1850
- if from_link is None :
1851
- from_link = self .base_link
1850
+ if startlink is None :
1851
+ startlink = self .base_link
1852
1852
1853
- if to_link is None :
1854
- to_link = self .ee_link
1853
+ if endlink is None :
1854
+ endlink = self .ee_link
1855
1855
1856
- links , n = self .get_path (from_link , to_link )
1856
+ links , n = self .get_path (startlink = startlink , endlink = endlink )
1857
1857
1858
1858
if q is None :
1859
1859
q = np .copy (self .q )
@@ -1873,7 +1873,7 @@ def indiv_calculation(link, link_col, q):
1873
1873
norm_h = np .expand_dims (np .r_ [norm , 0 , 0 , 0 ], axis = 0 )
1874
1874
1875
1875
Je = self .jacobe (
1876
- q , from_link = self .base_link , to_link = link ,
1876
+ q , startlink = self .base_link , endlink = link ,
1877
1877
offset = link_col .base )
1878
1878
n_dim = Je .shape [1 ]
1879
1879
dp = norm_h @ shape .v
@@ -1892,7 +1892,7 @@ def indiv_calculation(link, link_col, q):
1892
1892
1893
1893
for link_col in link .collision :
1894
1894
l_Ain , l_bin , d , wTcp = indiv_calculation (
1895
- link , link_col , q [: j ] )
1895
+ link , link_col , q )
1896
1896
1897
1897
if l_Ain is not None and l_bin is not None :
1898
1898
if Ain is None :
0 commit comments