@@ -493,7 +493,6 @@ def base_link(self, link):
493
493
# --------------------------------------------------------------------- #
494
494
# TODO get configuration string
495
495
496
-
497
496
@property
498
497
def ee_links (self ):
499
498
return self ._ee_links
@@ -570,72 +569,37 @@ def config(self):
570
569
571
570
# --------------------------------------------------------------------- #
572
571
573
- # def fkine(self, q=None):
574
- # '''
575
- # Evaluates the forward kinematics of a robot based on its ETS and
576
- # joint angles q.
577
-
578
- # T = fkine(q) evaluates forward kinematics for the robot at joint
579
- # configuration q.
580
-
581
- # T = fkine() as above except uses the stored q value of the
582
- # robot object.
583
-
584
- # Trajectory operation:
585
- # Calculates fkine for each point on a trajectory of joints q where
586
- # q is (nxm) and the returning SE3 in (m)
587
-
588
- # :param q: The joint angles/configuration of the robot (Optional,
589
- # if not supplied will use the stored q values).
590
- # :type q: float ndarray(n)
591
- # :return: The transformation matrix representing the pose of the
592
- # end-effector
593
- # :rtype: SE3
594
-
595
- # :notes:
596
- # - The robot's base or tool transform, if present, are incorporated
597
- # into the result.
598
-
599
- # :references:
600
- # - Kinematic Derivatives using the Elementary Transform
601
- # Sequence, J. Haviland and P. Corke
602
-
603
- # '''
604
-
605
- # trajn = 1
606
-
607
- # if q is None:
608
- # q = self.q
609
-
610
- # try:
611
- # q = getvector(q, self.n, 'col')
612
- # except ValueError:
613
- # trajn = q.shape[1]
614
- # verifymatrix(q, (self.n, trajn))
572
+ def fkine (self , q = None , from_link = None , to_link = None ):
573
+ '''
574
+ Evaluates the forward kinematics of a robot based on its ETS and
575
+ joint angles q.
615
576
616
- # for i in range(trajn):
617
- # j = 0
618
- # tr = self.base
577
+ T = fkine(q) evaluates forward kinematics for the robot at joint
578
+ configuration q.
619
579
620
- # for link in self._fkpath:
621
- # if link.isjoint:
622
- # T = link.A(q[j, i])
623
- # j += 1
624
- # else:
625
- # T = link.A()
580
+ T = fkine() as above except uses the stored q value of the
581
+ robot object.
626
582
627
- # tr = tr * T
583
+ Trajectory operation:
584
+ Calculates fkine for each point on a trajectory of joints q where
585
+ q is (nxm) and the returning SE3 in (m)
628
586
629
- # tr = tr * self.tool
587
+ :param q: The joint angles/configuration of the robot (Optional,
588
+ if not supplied will use the stored q values).
589
+ :type q: float ndarray(n)
590
+ :return: The transformation matrix representing the pose of the
591
+ end-effector
592
+ :rtype: SE3
630
593
631
- # if i == 0:
632
- # t = SE3(tr)
633
- # else:
634
- # t.append(tr)
594
+ :notes:
595
+ - The robot's base or tool transform, if present, are incorporated
596
+ into the result.
635
597
636
- # return t
598
+ :references:
599
+ - Kinematic Derivatives using the Elementary Transform
600
+ Sequence, J. Haviland and P. Corke
637
601
638
- def fkine ( self , q = None , from_link = None , to_link = None ):
602
+ '''
639
603
640
604
if from_link is None :
641
605
from_link = self .base_link
0 commit comments