@@ -817,27 +817,7 @@ def Ad(self):
817817 """
818818 return self .SE3 ().Ad ()
819819
820- def SE3 (self ):
821- """
822- Convert 3D twist to SE(3) matrix
823-
824- :return: an SE(3) representation
825- :rtype: SE3 instance
826-
827- ``S.SE3()`` is an SE3 object representing the homogeneous transformation
828- equivalent to the Twist3. This is the exponentiation of the twist vector.
829820
830- Example:
831-
832- .. runblock:: pycon
833-
834- >>> from spatialmath import Twist3
835- >>> S = Twist3.Rx(0.3)
836- >>> S.SE3()
837-
838- :seealso: :func:`Twist3.exp`
839- """
840- return SE3 (self .exp ())
841821
842822 def se3 (self ):
843823 """
@@ -933,30 +913,42 @@ def pole(self):
933913 """
934914 return np .cross (self .w , self .v ) / self .theta
935915
936- def theta (self ):
916+ def SE3 (self , theta = 1 , unit = 'rad' ):
937917 """
938- Twist rotation
939-
940- :return: rotation about the twist axis
941- :rtype: float
918+ Convert 3D twist to SE(3) matrix
942919
943- ``X.theta`` is the rotation about the twist axis in units of radians.
920+ :return: an SE(3) representation
921+ :rtype: SE3 instance
944922
945- If we consider the twist as a screw, this is the rotation about the
946- screw axis to achieve the rigid-body motion .
923+ ``S.SE3()`` is an SE3 object representing the homogeneous transformation
924+ equivalent to the Twist3. This is the exponentiation of the twist vector .
947925
948926 Example:
949927
950928 .. runblock:: pycon
951929
952- >>> from spatialmath import SE3, Twist3
953- >>> T = SE3(1, 2, 3) * SE3.Rx(0.3)
954- >>> S = Twist3(T)
955- >>> S.theta()
930+ >>> from spatialmath import Twist3
931+ >>> S = Twist3.Rx(0.3)
932+ >>> S.SE3()
933+
934+ :seealso: :func:`Twist3.exp`
956935 """
957- return base .norm ( self . w )
936+ theta = base .getunit ( theta , unit )
958937
959- def exp (self , theta = None , unit = 'rad' ):
938+ if base .isscalar (theta ):
939+ # theta is a scalar
940+ return SE3 (base .trexp (self .S * theta ))
941+ else :
942+ # theta is a vector
943+ if len (self ) == 1 :
944+ return SE3 ([base .trexp (self .S * t ) for t in theta ])
945+ elif len (self ) == len (theta ):
946+ return SE3 ([base .trexp (S * t ) for S , t in zip (self .data , theta )])
947+ else :
948+ raise ValueError ('length of twist and theta not consistent' )
949+ return SE3 (self .exp (theta ))
950+
951+ def exp (self , theta = 1 , unit = 'rad' ):
960952 """
961953 Exponentiate a 3D twist
962954
@@ -989,26 +981,9 @@ def exp(self, theta=None, unit='rad'):
989981
990982 :seealso: :func:`spatialmath.base.trexp`
991983 """
992- if unit != 'rad' and self .isprismatic :
993- print ('Twist3.exp: using degree mode for a prismatic twist' )
994-
995- if theta is None :
996- theta = 1
997- else :
998- theta = base .getunit (theta , unit )
999-
1000- if base .isscalar (theta ):
1001- # theta is a scalar
1002- return SE3 (base .trexp (self .S * theta ))
1003- else :
1004- # theta is a vector
1005- if len (self ) == 1 :
1006- return SE3 ([base .trexp (self .S * t ) for t in theta ])
1007- elif len (self ) == len (theta ):
1008- return SE3 ([base .trexp (S * t ) for S , t in zip (self .data , theta )])
1009- else :
1010- raise ValueError ('length of twist and theta not consistent' )
984+ theta = base .getunit (theta , unit )
1011985
986+ return base .trexp (self .S * theta )
1012987
1013988
1014989 # ------------------------- arithmetic -------------------------------#
@@ -1427,8 +1402,18 @@ def SE2(self, theta=1):
14271402
14281403 :seealso: :func:`Twist3.exp`
14291404 """
1405+ if unit != 'rad' and self .isprismatic :
1406+ print ('Twist3.exp: using degree mode for a prismatic twist' )
14301407
1431- return SE2 (self .exp ())
1408+ if theta is None :
1409+ theta = 1
1410+ else :
1411+ theta = base .getunit (theta , unit )
1412+
1413+ if base .isscalar (theta ):
1414+ return SE2 (base .trexp2 (self .S * theta ))
1415+ else :
1416+ return SE2 ([base .trexp2 (self .S * t ) for t in theta ])
14321417
14331418 def se2 (self ):
14341419 """
@@ -1488,19 +1473,7 @@ def exp(self, theta=None, unit='rad'):
14881473
14891474 :seealso: :func:`spatialmath.base.trexp2`
14901475 """
1491-
1492- if unit != 'rad' and self .isprismatic :
1493- print ('Twist3.exp: using degree mode for a prismatic twist' )
1494-
1495- if theta is None :
1496- theta = 1
1497- else :
1498- theta = base .getunit (theta , unit )
1499-
1500- if base .isscalar (theta ):
1501- return SE2 (base .trexp2 (self .S * theta ))
1502- else :
1503- return SE2 ([base .trexp2 (self .S * t ) for t in theta ])
1476+ return base .trexp2 (theta )
15041477
15051478
15061479 def unit (self ):
0 commit comments