@@ -863,18 +863,16 @@ def control_acknowledge_collision(self, wait_for_ready=True):
863
863
return self .__http_client .control_acknowledge_collision (wait_for_ready = wait_for_ready )
864
864
865
865
# Calc
866
- def calc_forward_kinematics (self , joints , fk_type = 'both' , tcp_config = None ):
866
+ def calc_forward_kinematics (self , joints , fk_type = None , tcp_config = None ):
867
867
"""Gives the position of the robot and orientation of end-effector in 3D space.
868
868
869
869
Args:
870
870
joints (list): a list of joint angles in RADIANS
871
- fk_type (str): 'position', 'orientation', 'both' are available FK types.
872
- Position is the XYZ of the end-effector in METERS from the middle-bottom-center of the robot.
873
- Orientation is the quaternion WXYZ values of the angle of the end-effector.
874
- tcp_config (dict, optional): dict containing TCP configuration.
871
+ fk_type (str): deprecated for 5.0.0
872
+ tcp_config (dict, optional): dict containing TCP configuration
875
873
876
874
Returns:
877
- dict: containing 'result', 'success' , and the FK type requested.
875
+ dict: containing 'result' value , 'position' dict , and 'orientation' dict
878
876
879
877
Raises:
880
878
EvaError: If it is not successful
@@ -883,10 +881,6 @@ def calc_forward_kinematics(self, joints, fk_type='both', tcp_config=None):
883
881
>>> eva.calc_forward_kinematics([0,0,0,0,0,0])
884
882
{'result': 'success', 'position': {'x': -0.065000005, 'y': -8.960835e-09, 'z': 0.87839997},
885
883
'orientation': {'w': 1, 'x': 0, 'y': 0, 'z': 0}}
886
- >>> eva.calc_forward_kinematics([0,0,0,0,0,0], fk_type='position')
887
- {'x': -0.065000005, 'y': -8.960835e-09, 'z': 0.87839997}
888
- >>> eva.calc_forward_kinematics([0,0,0,0,0,0], fk_type='orientation')
889
- {'w': 1, 'x': 0, 'y': 0, 'z': 0}
890
884
"""
891
885
self .__logger .debug ('Eva.calc_forward_kinematics called' )
892
886
return self .__http_client .calc_forward_kinematics (joints , fk_type = fk_type , tcp_config = tcp_config )
@@ -904,7 +898,7 @@ def calc_inverse_kinematics(self, guess, target_position, target_orientation, tc
904
898
orientation_type (str: optional): 'matrix', 'axis_angle', 'euler_zyx', or 'quat'(default) orientation types
905
899
906
900
Returns:
907
- dict : containing 'ik' dict with joint angles ( if successful) and 'result' of function call
901
+ list : containing joint angles if successful
908
902
909
903
Raises:
910
904
EvaError: If it is not successful
@@ -914,7 +908,7 @@ def calc_inverse_kinematics(self, guess, target_position, target_orientation, tc
914
908
>>> eva_orientation = {'w': 1, 'x': 0, 'y': 0, 'z': 0}
915
909
>>> eva_guess = [0, 0, 0, 0, 0, 0]
916
910
>>> robot.calc_inverse_kinematics(eva_guess, eva_position, eva_orientation)
917
- {'ik': {'joints': [0, 0, 0, 0, 0, 0], 'result': 'success'}}
911
+ [0, 0, 0, 0, 0, 0]
918
912
"""
919
913
self .__logger .debug ('Eva.calc_inverse_kinematics called' )
920
914
return self .__http_client .calc_inverse_kinematics (guess , target_position , target_orientation ,
@@ -982,7 +976,7 @@ def calc_rotate(self, joints, axis, offset, tcp_config=None):
982
976
TCP is considered to be the end-effector of the Robot.
983
977
984
978
Returns:
985
- dict : containing rotate dict with joint angles and result dict of success/failure
979
+ list : containing joint angles
986
980
987
981
Raises:
988
982
EvaError: If it is not successful
@@ -992,8 +986,7 @@ def calc_rotate(self, joints, axis, offset, tcp_config=None):
992
986
>>> "radius": 0.07,
993
987
>>> "rotations": {"x": 0, "y": 0, "z": 0}}
994
988
>>> robot.calc_rotate([0, 0, 0, 0, 0, 0], axis='y', offset=0.1, tcp_config=eva_tcp)
995
- {'rotate': {'joints': [-2.1625242e-09, -0.012081009, 0.09259305, 3.102962e-09, -0.1803575, -5.4273075e-09],
996
- 'result': 'success'}}
989
+ [-2.1625242e-09, -0.012081009, 0.09259305, 3.102962e-09, -0.1803575, -5.4273075e-09]
997
990
"""
998
991
self .__logger .debug ('Eva.calc_rotate called' )
999
992
return self .__http_client .calc_rotate (joints , axis , offset , tcp_config = tcp_config )
0 commit comments