Skip to content

Commit dd6687f

Browse files
fix(keyboard teleop), update(end-effector-frame), added not for urdf path
1 parent cd0a5d6 commit dd6687f

File tree

5 files changed

+10
-8
lines changed

5 files changed

+10
-8
lines changed

src/lerobot/model/kinematics.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ class RobotKinematics:
2121
def __init__(
2222
self,
2323
urdf_path: str,
24-
target_frame_name: str = "gripperframe",
24+
target_frame_name: str = "gripper_frame_link",
2525
joint_names: list[str] = None,
2626
):
2727
"""

src/lerobot/robots/so100_follower/config_so100_follower.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,10 +45,12 @@ class SO100FollowerEndEffectorConfig(SO100FollowerConfig):
4545
"""Configuration for the SO100FollowerEndEffector robot."""
4646

4747
# Path to URDF file for kinematics
48+
# NOTE: It is highly recommended to use the urdf in the SO-ARM100 repo:
49+
# https://github.com/TheRobotStudio/SO-ARM100/blob/main/Simulation/SO101/so101_new_calib.urdf
4850
urdf_path: str | None = None
4951

5052
# End-effector frame name in the URDF
51-
target_frame_name: str = "gripperframe"
53+
target_frame_name: str = "gripper_frame_link"
5254

5355
# Default bounds for the end-effector position (in meters)
5456
end_effector_bounds: dict[str, list[float]] = field(

src/lerobot/scripts/find_joint_limits.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
import draccus
3737
import numpy as np
3838

39+
from lerobot.common.utils.robot_utils import busy_wait
3940
from lerobot.model.kinematics import RobotKinematics
4041
from lerobot.robots import ( # noqa: F401
4142
RobotConfig,
@@ -50,7 +51,6 @@
5051
make_teleoperator_from_config,
5152
so100_leader,
5253
)
53-
from lerobot.common.utils.robot_utils import busy_wait
5454

5555

5656
@dataclass

src/lerobot/teleoperators/gamepad/gamepad_utils.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -307,8 +307,8 @@ def get_deltas(self):
307307
z_input = 0 if abs(z_input) < self.deadzone else z_input
308308

309309
# Calculate deltas (note: may need to invert axes depending on controller)
310-
delta_x = -x_input * self.x_step_size # Forward/backward
311-
delta_y = y_input * self.y_step_size # Left/right
310+
delta_x = -y_input * self.y_step_size # Forward/backward
311+
delta_y = -x_input * self.x_step_size # Left/right
312312
delta_z = -z_input * self.z_step_size # Up/down
313313

314314
return delta_x, delta_y, delta_z
@@ -465,8 +465,8 @@ def _update(self):
465465
def get_deltas(self):
466466
"""Get the current movement deltas from gamepad state."""
467467
# Calculate deltas - invert as needed based on controller orientation
468-
delta_x = -self.left_x * self.x_step_size # Forward/backward
469-
delta_y = self.left_y * self.y_step_size # Left/right
468+
delta_x = -self.left_y * self.y_step_size # Forward/backward
469+
delta_y = -self.left_x * self.x_step_size # Left/right
470470
delta_z = -self.right_y * self.z_step_size # Up/down
471471

472472
return delta_x, delta_y, delta_z

src/lerobot/teleoperators/keyboard/teleop_keyboard.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,7 @@ def get_action(self) -> dict[str, Any]:
196196
delta_x = 0.0
197197
delta_y = 0.0
198198
delta_z = 0.0
199+
gripper_action = 1.0
199200

200201
# Generate action based on current key states
201202
for key, val in self.current_pressed.items():
@@ -230,7 +231,6 @@ def get_action(self) -> dict[str, Any]:
230231
"delta_z": delta_z,
231232
}
232233

233-
gripper_action = 1 # default gripper action is to stay
234234
if self.config.use_gripper:
235235
action_dict["gripper"] = gripper_action
236236

0 commit comments

Comments
 (0)