|
13 | 13 | from rclpy.qos import (HistoryPolicy, QoSDurabilityPolicy, QoSProfile, |
14 | 14 | ReliabilityPolicy) |
15 | 15 | from reachy2_symbolic_ik.control_ik import ControlIK |
| 16 | + |
| 17 | +from reachy_utils.config import ReachyConfig |
16 | 18 | from reachy2_symbolic_ik.symbolic_ik import SymbolicIK |
17 | 19 | from reachy2_symbolic_ik.utils import (allow_multiturn, |
18 | 20 | get_best_continuous_theta, |
@@ -84,36 +86,12 @@ def __init__(self): |
84 | 86 | ) |
85 | 87 |
|
86 | 88 | self.orbita3D_max_angle = np.deg2rad(42.5) # 43.5 is too much |
87 | | - # Symbolic IK inits. |
88 | | - # A balanced position between elbow down and elbow at 90° |
89 | | - # self.prefered_theta = -4 * np.pi / 6 # 5 * np.pi / 4 # np.pi / 4 |
90 | | - # self.nb_search_points = 20 |
91 | | - # self.previous_theta = {} |
92 | | - # self.previous_sol = {} |
93 | 89 |
|
94 | 90 | for prefix in ("l", "r"): |
95 | 91 | arm = f"{prefix}_arm" |
96 | 92 |
|
97 | 93 | chain, fk_solver, ik_solver = generate_solver(self.urdf, "torso", f"{prefix}_arm_tip") |
98 | 94 |
|
99 | | - # self.symbolic_ik_solver[arm] = SymbolicIK( |
100 | | - # arm=arm, |
101 | | - # upper_arm_size=0.28, |
102 | | - # forearm_size=0.28, |
103 | | - # gripper_size=0.10, |
104 | | - # wrist_limit=np.rad2deg(self.orbita3D_max_angle), |
105 | | - # # This is the "correct" stuff for alpha |
106 | | - # # shoulder_orientation_offset=[10, 0, 15], |
107 | | - # # elbow_orientation_offset=[0, 0, 0], |
108 | | - # # This is the "wrong" values currently used by the alpha |
109 | | - # # shoulder_orientation_offset=[0, 0, 15], |
110 | | - # # shoulder_position=[-0.0479, -0.1913, 0.025], |
111 | | - # ) |
112 | | - |
113 | | - # self.previous_theta[arm] = None |
114 | | - # self.previous_sol[arm] = None |
115 | | - # self.last_call_t[arm] = 0 |
116 | | - |
117 | 95 | # We automatically loads the kinematics corresponding to the config |
118 | 96 | if chain.getNrOfJoints(): |
119 | 97 | self.logger.info(f'Found kinematics chain for "{arm}"!') |
@@ -324,10 +302,15 @@ def __init__(self): |
324 | 302 | self.chain["l_arm"].getNrOfJoints(), |
325 | 303 | ) |
326 | 304 | current_pose = [current_pose_r, current_pose_l] |
| 305 | + |
| 306 | + reachy_config = ReachyConfig() |
| 307 | + |
327 | 308 | self.control_ik = ControlIK( |
328 | 309 | logger=self.logger, |
329 | 310 | current_joints=current_joints, |
330 | 311 | current_pose=current_pose, |
| 312 | + urdf=self.urdf, |
| 313 | + reachy_model=reachy_config.model, |
331 | 314 | ) |
332 | 315 |
|
333 | 316 | self.logger.info(f"Kinematics node ready!") |
|
0 commit comments