mirror of
https://github.com/huggingface/lerobot.git
synced 2026-05-16 00:59:46 +00:00
9183083e75
* refactor(processor): split action from policy, robots and environment - Updated function names to robot_action_to_transition and robot_transition_to_action across multiple files to better reflect their purpose in processing robot actions. - Adjusted references in the RobotProcessorPipeline and related components to ensure compatibility with the new naming convention. - Enhanced type annotations for action parameters to improve code readability and maintainability. * refactor(converters): rename robot_transition_to_action to transition_to_robot_action - Updated function names across multiple files to improve clarity and consistency in processing robot actions. - Adjusted references in RobotProcessorPipeline and related components to align with the new naming convention. - Simplified action handling in the AddBatchDimensionProcessorStep by removing unnecessary checks for action presence. * refactor(converters): update references to transition_to_robot_action - Renamed all instances of robot_transition_to_action to transition_to_robot_action across multiple files for consistency and clarity in the processing of robot actions. - Adjusted the RobotProcessorPipeline configurations to reflect the new naming convention, enhancing code readability. * refactor(processor): update Torch2NumpyActionProcessorStep to extend ActionProcessorStep - Changed the base class of Torch2NumpyActionProcessorStep from PolicyActionProcessorStep to ActionProcessorStep, aligning it with the current architecture of action processing. - This modification enhances the clarity of the class's role in the processing pipeline. * fix(processor): main action processor can take also EnvAction --------- Co-authored-by: Steven Palma <steven.palma@huggingface.co>
160 lines
5.5 KiB
Python
160 lines
5.5 KiB
Python
# !/usr/bin/env python
|
|
|
|
# Copyright 2025 The HuggingFace Inc. team. All rights reserved.
|
|
#
|
|
# Licensed under the Apache License, Version 2.0 (the "License");
|
|
# you may not use this file except in compliance with the License.
|
|
# You may obtain a copy of the License at
|
|
#
|
|
# http://www.apache.org/licenses/LICENSE-2.0
|
|
#
|
|
# Unless required by applicable law or agreed to in writing, software
|
|
# distributed under the License is distributed on an "AS IS" BASIS,
|
|
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
|
# See the License for the specific language governing permissions and
|
|
# limitations under the License.
|
|
|
|
from lerobot.cameras.opencv.configuration_opencv import OpenCVCameraConfig
|
|
from lerobot.datasets.lerobot_dataset import LeRobotDataset
|
|
from lerobot.datasets.pipeline_features import aggregate_pipeline_dataset_features, create_initial_features
|
|
from lerobot.datasets.utils import combine_feature_dicts
|
|
from lerobot.model.kinematics import RobotKinematics
|
|
from lerobot.policies.act.modeling_act import ACTPolicy
|
|
from lerobot.policies.factory import make_pre_post_processors
|
|
from lerobot.processor import RobotProcessorPipeline
|
|
from lerobot.processor.converters import (
|
|
identity_transition,
|
|
observation_to_transition,
|
|
transition_to_robot_action,
|
|
)
|
|
from lerobot.record import record_loop
|
|
from lerobot.robots.so100_follower.config_so100_follower import SO100FollowerConfig
|
|
from lerobot.robots.so100_follower.robot_kinematic_processor import (
|
|
AddRobotObservationAsComplimentaryData,
|
|
ForwardKinematicsJointsToEE,
|
|
InverseKinematicsEEToJoints,
|
|
)
|
|
from lerobot.robots.so100_follower.so100_follower import SO100Follower
|
|
from lerobot.utils.control_utils import init_keyboard_listener
|
|
from lerobot.utils.utils import log_say
|
|
from lerobot.utils.visualization_utils import _init_rerun
|
|
|
|
NUM_EPISODES = 5
|
|
FPS = 30
|
|
EPISODE_TIME_SEC = 60
|
|
TASK_DESCRIPTION = "My task description"
|
|
HF_MODEL_ID = "<hf_username>/<model_repo_id>"
|
|
HF_DATASET_ID = "<hf_username>/<dataset_repo_id>"
|
|
|
|
# Initialize the robot with degrees
|
|
camera_config = {"front": OpenCVCameraConfig(index_or_path=0, width=640, height=480, fps=FPS)}
|
|
robot_config = SO100FollowerConfig(
|
|
port="/dev/tty.usbmodem58760434471",
|
|
id="my_awesome_follower_arm",
|
|
cameras=camera_config,
|
|
use_degrees=True,
|
|
)
|
|
|
|
# Initialize the robot
|
|
robot = SO100Follower(robot_config)
|
|
|
|
# NOTE: It is highly recommended to use the urdf in the SO-ARM100 repo: https://github.com/TheRobotStudio/SO-ARM100/blob/main/Simulation/SO101/so101_new_calib.urdf
|
|
kinematics_solver = RobotKinematics(
|
|
urdf_path="./src/lerobot/teleoperators/sim/so101_new_calib.urdf",
|
|
target_frame_name="gripper_frame_link",
|
|
joint_names=list(robot.bus.motors.keys()),
|
|
)
|
|
|
|
# Build pipeline to convert ee pose action to joint action
|
|
robot_ee_to_joints_processor = RobotProcessorPipeline(
|
|
steps=[
|
|
AddRobotObservationAsComplimentaryData(robot=robot),
|
|
InverseKinematicsEEToJoints(
|
|
kinematics=kinematics_solver,
|
|
motor_names=list(robot.bus.motors.keys()),
|
|
initial_guess_current_joints=True,
|
|
),
|
|
],
|
|
to_transition=identity_transition,
|
|
to_output=transition_to_robot_action,
|
|
)
|
|
|
|
# Build pipeline to convert joint observation to ee pose observation
|
|
robot_joints_to_ee_pose_processor = RobotProcessorPipeline(
|
|
steps=[
|
|
ForwardKinematicsJointsToEE(kinematics=kinematics_solver, motor_names=list(robot.bus.motors.keys()))
|
|
],
|
|
to_transition=observation_to_transition,
|
|
to_output=identity_transition,
|
|
)
|
|
|
|
# Build dataset action and gripper features
|
|
action_ee_and_gripper = aggregate_pipeline_dataset_features(
|
|
pipeline=robot_ee_to_joints_processor,
|
|
initial_features=create_initial_features(),
|
|
use_videos=True,
|
|
patterns=["action.ee", "action.gripper.pos", "observation.state.gripper.pos"],
|
|
) # Get all ee action features + gripper pos action features
|
|
|
|
# Build dataset observation features
|
|
obs_ee = aggregate_pipeline_dataset_features(
|
|
pipeline=robot_joints_to_ee_pose_processor,
|
|
initial_features=create_initial_features(observation=robot.observation_features),
|
|
use_videos=True,
|
|
patterns=["observation.state.ee"],
|
|
) # Get all ee observation features
|
|
|
|
dataset_features = combine_feature_dicts(obs_ee, action_ee_and_gripper)
|
|
|
|
print("All dataset features: ", dataset_features)
|
|
|
|
# Create the dataset
|
|
dataset = LeRobotDataset.create(
|
|
repo_id=HF_DATASET_ID,
|
|
fps=FPS,
|
|
features=dataset_features,
|
|
robot_type=robot.name,
|
|
use_videos=True,
|
|
image_writer_threads=4,
|
|
)
|
|
|
|
# Initialize the keyboard listener and rerun visualization
|
|
_, events = init_keyboard_listener()
|
|
_init_rerun(session_name="recording_phone")
|
|
|
|
# Connect the robot and teleoperator
|
|
robot.connect()
|
|
|
|
episode_idx = 0
|
|
|
|
policy = ACTPolicy.from_pretrained(HF_MODEL_ID)
|
|
preprocessor, postprocessor = make_pre_post_processors(
|
|
policy_cfg=policy,
|
|
pretrained_path=HF_MODEL_ID,
|
|
dataset_stats=dataset.meta.stats,
|
|
)
|
|
|
|
for episode_idx in range(NUM_EPISODES):
|
|
log_say(f"Running inference, recording eval episode {episode_idx + 1} of {NUM_EPISODES}")
|
|
|
|
record_loop(
|
|
robot=robot,
|
|
events=events,
|
|
fps=FPS,
|
|
policy=policy,
|
|
preprocessor=preprocessor,
|
|
postprocessor=postprocessor,
|
|
dataset=dataset,
|
|
control_time_s=EPISODE_TIME_SEC,
|
|
single_task=TASK_DESCRIPTION,
|
|
display_data=True,
|
|
robot_action_processor=robot_ee_to_joints_processor,
|
|
robot_observation_processor=robot_joints_to_ee_pose_processor,
|
|
)
|
|
dataset.save_episode()
|
|
|
|
# Clean up
|
|
log_say("Stop recording")
|
|
robot.disconnect()
|
|
dataset.push_to_hub()
|