|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
import time
|
|
|
|
|
|
from lerobot.model.kinematics import RobotKinematics
|
|
|
from lerobot.processor import RobotAction, RobotObservation, RobotProcessorPipeline
|
|
|
from lerobot.processor.converters import (
|
|
|
robot_action_observation_to_transition,
|
|
|
robot_action_to_transition,
|
|
|
transition_to_robot_action,
|
|
|
)
|
|
|
from lerobot.robots.so100_follower.config_so100_follower import SO100FollowerConfig
|
|
|
from lerobot.robots.so100_follower.robot_kinematic_processor import (
|
|
|
EEBoundsAndSafety,
|
|
|
ForwardKinematicsJointsToEE,
|
|
|
InverseKinematicsEEToJoints,
|
|
|
)
|
|
|
from lerobot.robots.so100_follower.so100_follower import SO100Follower
|
|
|
from lerobot.teleoperators.so100_leader.config_so100_leader import SO100LeaderConfig
|
|
|
from lerobot.teleoperators.so100_leader.so100_leader import SO100Leader
|
|
|
from lerobot.utils.robot_utils import busy_wait
|
|
|
from lerobot.utils.visualization_utils import init_rerun, log_rerun_data
|
|
|
|
|
|
FPS = 30
|
|
|
|
|
|
|
|
|
follower_config = SO100FollowerConfig(
|
|
|
port="/dev/tty.usbmodem5A460814411", id="my_awesome_follower_arm", use_degrees=True
|
|
|
)
|
|
|
leader_config = SO100LeaderConfig(port="/dev/tty.usbmodem5A460819811", id="my_awesome_leader_arm")
|
|
|
|
|
|
|
|
|
follower = SO100Follower(follower_config)
|
|
|
leader = SO100Leader(leader_config)
|
|
|
|
|
|
|
|
|
follower_kinematics_solver = RobotKinematics(
|
|
|
urdf_path="./SO101/so101_new_calib.urdf",
|
|
|
target_frame_name="gripper_frame_link",
|
|
|
joint_names=list(follower.bus.motors.keys()),
|
|
|
)
|
|
|
|
|
|
|
|
|
leader_kinematics_solver = RobotKinematics(
|
|
|
urdf_path="./SO101/so101_new_calib.urdf",
|
|
|
target_frame_name="gripper_frame_link",
|
|
|
joint_names=list(leader.bus.motors.keys()),
|
|
|
)
|
|
|
|
|
|
|
|
|
leader_to_ee = RobotProcessorPipeline[RobotAction, RobotAction](
|
|
|
steps=[
|
|
|
ForwardKinematicsJointsToEE(
|
|
|
kinematics=leader_kinematics_solver, motor_names=list(leader.bus.motors.keys())
|
|
|
),
|
|
|
],
|
|
|
to_transition=robot_action_to_transition,
|
|
|
to_output=transition_to_robot_action,
|
|
|
)
|
|
|
|
|
|
|
|
|
ee_to_follower_joints = RobotProcessorPipeline[tuple[RobotAction, RobotObservation], RobotAction](
|
|
|
[
|
|
|
EEBoundsAndSafety(
|
|
|
end_effector_bounds={"min": [-1.0, -1.0, -1.0], "max": [1.0, 1.0, 1.0]},
|
|
|
max_ee_step_m=0.10,
|
|
|
),
|
|
|
InverseKinematicsEEToJoints(
|
|
|
kinematics=follower_kinematics_solver,
|
|
|
motor_names=list(follower.bus.motors.keys()),
|
|
|
initial_guess_current_joints=False,
|
|
|
),
|
|
|
],
|
|
|
to_transition=robot_action_observation_to_transition,
|
|
|
to_output=transition_to_robot_action,
|
|
|
)
|
|
|
|
|
|
|
|
|
follower.connect()
|
|
|
leader.connect()
|
|
|
|
|
|
|
|
|
init_rerun(session_name="so100_so100_EE_teleop")
|
|
|
|
|
|
print("Starting teleop loop...")
|
|
|
while True:
|
|
|
t0 = time.perf_counter()
|
|
|
|
|
|
|
|
|
robot_obs = follower.get_observation()
|
|
|
|
|
|
|
|
|
leader_joints_obs = leader.get_action()
|
|
|
|
|
|
|
|
|
leader_ee_act = leader_to_ee(leader_joints_obs)
|
|
|
|
|
|
|
|
|
follower_joints_act = ee_to_follower_joints((leader_ee_act, robot_obs))
|
|
|
|
|
|
|
|
|
_ = follower.send_action(follower_joints_act)
|
|
|
|
|
|
|
|
|
log_rerun_data(observation=leader_ee_act, action=follower_joints_act)
|
|
|
|
|
|
busy_wait(max(1.0 / FPS - (time.perf_counter() - t0), 0.0))
|
|
|
|