@@ -75,6 +75,7 @@ def inverse(
7575 q0 : np .ndarray [tuple [typing .Literal [7 ]], np .dtype [np .float64 ]] | None = None ,
7676 tcp_offset : np .ndarray [tuple [typing .Literal [4 ], typing .Literal [4 ]], np .dtype [np .float64 ]] | None = None ,
7777 allow_elbow_flips : bool = False ,
78+ q7 : float = np .pi / 4 ,
7879 ) -> np .ndarray [tuple [typing .Literal [7 ]], np .dtype [np .float64 ]] | None :
7980 """Compute the inverse kinematics for the given end-effector pose.
8081 Args:
@@ -87,13 +88,13 @@ def inverse(
8788 np.ndarray | None: A 7-element array representing the joint angles if a solution is found; otherwise, None.
8889 """
8990 new_pose = pose @ self .pose_inverse (tcp_offset ) if tcp_offset is not None else pose
90- q = ik (new_pose , q0 , is_fr3 = (self .robot_type == RobotType .FR3 ))
91+ q = ik (new_pose , q0 , q7 = q7 , is_fr3 = (self .robot_type == RobotType .FR3 ))
9192
9293 if not np .isnan (q ).any ():
9394 return q
9495 if not allow_elbow_flips :
9596 return None
96- qs = ik_full (new_pose , q0 , is_fr3 = (self .robot_type == RobotType .FR3 ))
97+ qs = ik_full (new_pose , q0 , q7 = q7 , is_fr3 = (self .robot_type == RobotType .FR3 ))
9798 qs_list = list (qs )
9899 # drop nan solutions
99100 qs_list = [q for q in qs_list if not np .isnan (q ).any ()]
0 commit comments