@@ -245,7 +245,7 @@ def ikine_LM(
245245 """ # noqa E501
246246
247247 if not isinstance (T , SE3 ):
248- T = SE3 ( T )
248+ raise TypeError ( 'argument must be SE3' )
249249
250250 solutions = []
251251
@@ -304,19 +304,7 @@ def ikine_LM(
304304 tcount = 0 # Total iteration count
305305 rejcount = 0 # Rejected step count
306306 nm = 0
307-
308- # bool vector indicating revolute joints
309- # revolutes = np.array([link.isrevolute for link in self])
310-
311- revolutes = []
312-
313- # This is a mixin class inherited by robot classes
314- # Therefore it will never be used on its own and the
315- # LGTM issue can be ignored
316- for link in self : # lgtm [py/non-iterable-in-for-loop]
317- if isinstance (self , rtb .DHRobot ) or link .isjoint :
318- revolutes .append (link .isrevolute )
319- revolutes = np .array (revolutes )
307+ revolutes = self .revolutejoints
320308
321309 q = q0
322310 for Tk in T :
@@ -523,7 +511,7 @@ def ikine_LMS(
523511 """ # noqa E501
524512
525513 if not isinstance (T , SE3 ):
526- T = SE3 ( T )
514+ raise TypeError ( 'argument must be SE3' )
527515
528516 solutions = []
529517
@@ -542,19 +530,7 @@ def ikine_LMS(
542530 W = np .diag (mask )
543531
544532 tcount = 0 # Total iteration count
545-
546- # bool vector indicating revolute joints
547- # joints = np.array([link.isjoint for link in self])
548- # revolutes = np.array([link.isrevolute for link in self])
549- revolutes = []
550-
551- # This is a mixin class inherited by robot classes
552- # Therefore it will never be used on its own and the
553- # LGTM issue can be ignored
554- for link in self : # lgtm [py/non-iterable-in-for-loop]
555- if isinstance (self , rtb .DHRobot ) or link .isjoint :
556- revolutes .append (link .isrevolute )
557- revolutes = np .array (revolutes )
533+ revolutes = self .revolutejoints
558534
559535 q = q0
560536 for Tk in T :
@@ -590,8 +566,6 @@ def ikine_LMS(
590566 # print(J)
591567
592568 # Wrap angles for revolute joints
593- print (revolutes )
594- print (q )
595569 k = np .logical_and (q > np .pi , revolutes )
596570 q [k ] -= 2 * np .pi
597571
@@ -729,7 +703,7 @@ def ikine_min(
729703 """ # noqa E501
730704
731705 if not isinstance (T , SE3 ):
732- T = SE3 ( T )
706+ raise TypeError ( 'argument must be SE3' )
733707
734708 if q0 is None :
735709 q0 = np .zeros ((self .n ))
@@ -818,7 +792,7 @@ def ikine_global(
818792 # dual_annealing: bounds
819793
820794 if not isinstance (T , SE3 ):
821- T = SE3 ( T )
795+ raise TypeError ( 'argument must be SE3' )
822796
823797 solutions = []
824798
0 commit comments