mirror of
https://github.com/huggingface/lerobot.git
synced 2026-05-23 12:40:08 +00:00
chore(processor): rename specialized processor -> XYZProcessorStep (#1852)
This commit is contained in:
@@ -21,7 +21,7 @@ from lerobot.configs.types import PolicyFeature
|
||||
from lerobot.constants import POSTPROCESSOR_DEFAULT_NAME, PREPROCESSOR_DEFAULT_NAME
|
||||
from lerobot.policies.pi0.configuration_pi0 import PI0Config
|
||||
from lerobot.processor import (
|
||||
ComplementaryDataProcessor,
|
||||
ComplementaryDataProcessorStep,
|
||||
DataProcessorPipeline,
|
||||
DeviceProcessor,
|
||||
NormalizerProcessor,
|
||||
@@ -36,7 +36,7 @@ from lerobot.processor import (
|
||||
|
||||
|
||||
@ProcessorStepRegistry.register(name="pi0_new_line_processor")
|
||||
class Pi0NewLineProcessor(ComplementaryDataProcessor):
|
||||
class Pi0NewLineProcessor(ComplementaryDataProcessorStep):
|
||||
"""Add a new line to the end of the task if it doesn't have one.
|
||||
This is required for the PaliGemma tokenizer.
|
||||
"""
|
||||
|
||||
@@ -19,7 +19,7 @@ from lerobot.policies.sac.reward_model.configuration_classifier import RewardCla
|
||||
from lerobot.processor import (
|
||||
DataProcessorPipeline,
|
||||
DeviceProcessor,
|
||||
IdentityProcessor,
|
||||
IdentityProcessorStep,
|
||||
NormalizerProcessor,
|
||||
ProcessorKwargs,
|
||||
)
|
||||
@@ -45,7 +45,7 @@ def make_classifier_processor(
|
||||
),
|
||||
DeviceProcessor(device=config.device),
|
||||
]
|
||||
output_steps = [DeviceProcessor(device="cpu"), IdentityProcessor()]
|
||||
output_steps = [DeviceProcessor(device="cpu"), IdentityProcessorStep()]
|
||||
|
||||
return (
|
||||
DataProcessorPipeline(
|
||||
|
||||
@@ -20,7 +20,7 @@ from lerobot.configs.types import PolicyFeature
|
||||
from lerobot.constants import POSTPROCESSOR_DEFAULT_NAME, PREPROCESSOR_DEFAULT_NAME
|
||||
from lerobot.policies.smolvla.configuration_smolvla import SmolVLAConfig
|
||||
from lerobot.processor import (
|
||||
ComplementaryDataProcessor,
|
||||
ComplementaryDataProcessorStep,
|
||||
DataProcessorPipeline,
|
||||
DeviceProcessor,
|
||||
NormalizerProcessor,
|
||||
@@ -82,7 +82,7 @@ def make_smolvla_pre_post_processors(
|
||||
|
||||
|
||||
@ProcessorStepRegistry.register(name="smolvla_new_line_processor")
|
||||
class SmolVLANewLineProcessor(ComplementaryDataProcessor):
|
||||
class SmolVLANewLineProcessor(ComplementaryDataProcessorStep):
|
||||
"""Add a new line to the end of the task if it doesn't have one."""
|
||||
|
||||
def complementary_data(self, complementary_data):
|
||||
|
||||
@@ -39,37 +39,37 @@ from .joint_observations_processor import JointVelocityProcessor, MotorCurrentPr
|
||||
from .normalize_processor import NormalizerProcessor, UnnormalizerProcessor, hotswap_stats
|
||||
from .observation_processor import VanillaObservationProcessor
|
||||
from .pipeline import (
|
||||
ActionProcessor,
|
||||
ComplementaryDataProcessor,
|
||||
ActionProcessorStep,
|
||||
ComplementaryDataProcessorStep,
|
||||
DataProcessorPipeline,
|
||||
DoneProcessor,
|
||||
IdentityProcessor,
|
||||
InfoProcessor,
|
||||
ObservationProcessor,
|
||||
DoneProcessorStep,
|
||||
IdentityProcessorStep,
|
||||
InfoProcessorStep,
|
||||
ObservationProcessorStep,
|
||||
ProcessorKwargs,
|
||||
ProcessorStep,
|
||||
ProcessorStepRegistry,
|
||||
RewardProcessor,
|
||||
TruncatedProcessor,
|
||||
RewardProcessorStep,
|
||||
TruncatedProcessorStep,
|
||||
)
|
||||
from .rename_processor import RenameProcessor
|
||||
from .tokenizer_processor import TokenizerProcessor
|
||||
|
||||
__all__ = [
|
||||
"ActionProcessor",
|
||||
"ActionProcessorStep",
|
||||
"AddTeleopActionAsComplimentaryData",
|
||||
"AddTeleopEventsAsInfo",
|
||||
"ComplementaryDataProcessor",
|
||||
"ComplementaryDataProcessorStep",
|
||||
"batch_to_transition",
|
||||
"create_transition",
|
||||
"DeviceProcessor",
|
||||
"DoneProcessor",
|
||||
"DoneProcessorStep",
|
||||
"EnvTransition",
|
||||
"GripperPenaltyProcessor",
|
||||
"hotswap_stats",
|
||||
"IdentityProcessor",
|
||||
"IdentityProcessorStep",
|
||||
"ImageCropResizeProcessor",
|
||||
"InfoProcessor",
|
||||
"InfoProcessorStep",
|
||||
"InterventionActionProcessor",
|
||||
"JointVelocityProcessor",
|
||||
"MapDeltaActionToRobotAction",
|
||||
@@ -78,13 +78,13 @@ __all__ = [
|
||||
"MotorCurrentProcessor",
|
||||
"NormalizerProcessor",
|
||||
"Numpy2TorchActionProcessor",
|
||||
"ObservationProcessor",
|
||||
"ObservationProcessorStep",
|
||||
"ProcessorKwargs",
|
||||
"ProcessorStep",
|
||||
"ProcessorStepRegistry",
|
||||
"RenameProcessor",
|
||||
"RewardClassifierProcessor",
|
||||
"RewardProcessor",
|
||||
"RewardProcessorStep",
|
||||
"DataProcessorPipeline",
|
||||
"TimeLimitProcessor",
|
||||
"ToBatchProcessor",
|
||||
@@ -93,7 +93,7 @@ __all__ = [
|
||||
"transition_to_batch",
|
||||
"transition_to_dataset_frame",
|
||||
"TransitionKey",
|
||||
"TruncatedProcessor",
|
||||
"TruncatedProcessorStep",
|
||||
"UnnormalizerProcessor",
|
||||
"VanillaObservationProcessor",
|
||||
]
|
||||
|
||||
@@ -20,9 +20,9 @@ from lerobot.constants import OBS_ENV_STATE, OBS_IMAGE, OBS_IMAGES, OBS_STATE
|
||||
|
||||
from .core import EnvTransition
|
||||
from .pipeline import (
|
||||
ActionProcessor,
|
||||
ComplementaryDataProcessor,
|
||||
ObservationProcessor,
|
||||
ActionProcessorStep,
|
||||
ComplementaryDataProcessorStep,
|
||||
ObservationProcessorStep,
|
||||
ProcessorStep,
|
||||
ProcessorStepRegistry,
|
||||
)
|
||||
@@ -30,7 +30,7 @@ from .pipeline import (
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register(name="to_batch_processor_action")
|
||||
class ToBatchProcessorAction(ActionProcessor):
|
||||
class ToBatchProcessorAction(ActionProcessorStep):
|
||||
"""Process action component in-place, adding batch dimension if needed."""
|
||||
|
||||
def action(self, action):
|
||||
@@ -45,7 +45,7 @@ class ToBatchProcessorAction(ActionProcessor):
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register(name="to_batch_processor_observation")
|
||||
class ToBatchProcessorObservation(ObservationProcessor):
|
||||
class ToBatchProcessorObservation(ObservationProcessorStep):
|
||||
"""Process observation component in-place, adding batch dimensions where needed."""
|
||||
|
||||
def observation(self, observation):
|
||||
@@ -74,7 +74,7 @@ class ToBatchProcessorObservation(ObservationProcessor):
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register(name="to_batch_processor_complementary_data")
|
||||
class ToBatchProcessorComplementaryData(ComplementaryDataProcessor):
|
||||
class ToBatchProcessorComplementaryData(ComplementaryDataProcessorStep):
|
||||
"""Process complementary data in-place, handling task field batching."""
|
||||
|
||||
def complementary_data(self, complementary_data):
|
||||
|
||||
@@ -21,12 +21,12 @@ from torch import Tensor
|
||||
from lerobot.configs.types import FeatureType, PolicyFeature
|
||||
from lerobot.constants import ACTION
|
||||
|
||||
from .pipeline import ActionProcessor, ProcessorStepRegistry
|
||||
from .pipeline import ActionProcessorStep, ProcessorStepRegistry
|
||||
|
||||
|
||||
@ProcessorStepRegistry.register("map_tensor_to_delta_action_dict")
|
||||
@dataclass
|
||||
class MapTensorToDeltaActionDict(ActionProcessor):
|
||||
class MapTensorToDeltaActionDict(ActionProcessorStep):
|
||||
"""
|
||||
Map a tensor to a delta action dictionary.
|
||||
"""
|
||||
@@ -58,7 +58,7 @@ class MapTensorToDeltaActionDict(ActionProcessor):
|
||||
|
||||
@ProcessorStepRegistry.register("map_delta_action_to_robot_action")
|
||||
@dataclass
|
||||
class MapDeltaActionToRobotAction(ActionProcessor):
|
||||
class MapDeltaActionToRobotAction(ActionProcessorStep):
|
||||
"""
|
||||
Map delta actions from teleoperators (gamepad, keyboard) to robot target actions
|
||||
for use with inverse kinematics processors.
|
||||
|
||||
@@ -19,12 +19,12 @@ import torch
|
||||
from lerobot.configs.types import PolicyFeature
|
||||
|
||||
from .converters import to_tensor
|
||||
from .pipeline import ActionProcessor, ProcessorStepRegistry
|
||||
from .pipeline import ActionProcessorStep, ProcessorStepRegistry
|
||||
|
||||
|
||||
@ProcessorStepRegistry.register("torch2numpy_action_processor")
|
||||
@dataclass
|
||||
class Torch2NumpyActionProcessor(ActionProcessor):
|
||||
class Torch2NumpyActionProcessor(ActionProcessorStep):
|
||||
"""Convert PyTorch tensor actions to NumPy arrays."""
|
||||
|
||||
squeeze_batch_dim: bool = True
|
||||
@@ -56,7 +56,7 @@ class Torch2NumpyActionProcessor(ActionProcessor):
|
||||
|
||||
@ProcessorStepRegistry.register("numpy2torch_action_processor")
|
||||
@dataclass
|
||||
class Numpy2TorchActionProcessor(ActionProcessor):
|
||||
class Numpy2TorchActionProcessor(ActionProcessorStep):
|
||||
"""Convert NumPy array action to PyTorch tensor."""
|
||||
|
||||
def action(self, action: np.ndarray) -> torch.Tensor:
|
||||
|
||||
@@ -14,12 +14,12 @@ from lerobot.teleoperators.utils import TeleopEvents
|
||||
|
||||
from .core import EnvTransition, TransitionKey
|
||||
from .pipeline import (
|
||||
ComplementaryDataProcessor,
|
||||
InfoProcessor,
|
||||
ObservationProcessor,
|
||||
ComplementaryDataProcessorStep,
|
||||
InfoProcessorStep,
|
||||
ObservationProcessorStep,
|
||||
ProcessorStep,
|
||||
ProcessorStepRegistry,
|
||||
TruncatedProcessor,
|
||||
TruncatedProcessorStep,
|
||||
)
|
||||
|
||||
GRIPPER_KEY = "gripper"
|
||||
@@ -29,7 +29,7 @@ TELEOP_ACTION_KEY = "teleop_action"
|
||||
|
||||
@ProcessorStepRegistry.register("add_teleop_action_as_complementary_data")
|
||||
@dataclass
|
||||
class AddTeleopActionAsComplimentaryData(ComplementaryDataProcessor):
|
||||
class AddTeleopActionAsComplimentaryData(ComplementaryDataProcessorStep):
|
||||
"""Add teleoperator action to transition complementary data."""
|
||||
|
||||
teleop_device: Teleoperator
|
||||
@@ -45,7 +45,7 @@ class AddTeleopActionAsComplimentaryData(ComplementaryDataProcessor):
|
||||
|
||||
@ProcessorStepRegistry.register("add_teleop_action_as_info")
|
||||
@dataclass
|
||||
class AddTeleopEventsAsInfo(InfoProcessor):
|
||||
class AddTeleopEventsAsInfo(InfoProcessorStep):
|
||||
"""Add teleoperator control events to transition info."""
|
||||
|
||||
teleop_device: Teleoperator
|
||||
@@ -62,7 +62,7 @@ class AddTeleopEventsAsInfo(InfoProcessor):
|
||||
|
||||
@ProcessorStepRegistry.register("image_crop_resize_processor")
|
||||
@dataclass
|
||||
class ImageCropResizeProcessor(ObservationProcessor):
|
||||
class ImageCropResizeProcessor(ObservationProcessorStep):
|
||||
"""Crop and resize image observations."""
|
||||
|
||||
crop_params_dict: dict[str, tuple[int, int, int, int]] | None = None
|
||||
@@ -112,7 +112,7 @@ class ImageCropResizeProcessor(ObservationProcessor):
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register("time_limit_processor")
|
||||
class TimeLimitProcessor(TruncatedProcessor):
|
||||
class TimeLimitProcessor(TruncatedProcessorStep):
|
||||
"""Track episode steps and enforce time limits."""
|
||||
|
||||
max_episode_steps: int
|
||||
@@ -139,7 +139,7 @@ class TimeLimitProcessor(TruncatedProcessor):
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register("gripper_penalty_processor")
|
||||
class GripperPenaltyProcessor(ComplementaryDataProcessor):
|
||||
class GripperPenaltyProcessor(ComplementaryDataProcessorStep):
|
||||
"""Apply penalty for inappropriate gripper usage."""
|
||||
|
||||
penalty: float = -0.01
|
||||
|
||||
@@ -6,7 +6,7 @@ import torch
|
||||
from lerobot.configs.types import PolicyFeature
|
||||
from lerobot.constants import OBS_STATE
|
||||
from lerobot.processor.pipeline import (
|
||||
ObservationProcessor,
|
||||
ObservationProcessorStep,
|
||||
ProcessorStepRegistry,
|
||||
)
|
||||
from lerobot.robots import Robot
|
||||
@@ -14,7 +14,7 @@ from lerobot.robots import Robot
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register("joint_velocity_processor")
|
||||
class JointVelocityProcessor(ObservationProcessor):
|
||||
class JointVelocityProcessor(ObservationProcessorStep):
|
||||
"""Add joint velocity information to observations."""
|
||||
|
||||
dt: float = 0.1
|
||||
@@ -67,7 +67,7 @@ class JointVelocityProcessor(ObservationProcessor):
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register("current_processor")
|
||||
class MotorCurrentProcessor(ObservationProcessor):
|
||||
class MotorCurrentProcessor(ObservationProcessorStep):
|
||||
"""Add motor current information to observations."""
|
||||
|
||||
robot: Robot | None = None
|
||||
|
||||
@@ -23,12 +23,12 @@ from torch import Tensor
|
||||
from lerobot.configs.types import PolicyFeature
|
||||
from lerobot.constants import OBS_ENV_STATE, OBS_IMAGE, OBS_IMAGES, OBS_STATE
|
||||
|
||||
from .pipeline import ObservationProcessor, ProcessorStepRegistry
|
||||
from .pipeline import ObservationProcessorStep, ProcessorStepRegistry
|
||||
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register(name="observation_processor")
|
||||
class VanillaObservationProcessor(ObservationProcessor):
|
||||
class VanillaObservationProcessor(ObservationProcessorStep):
|
||||
"""
|
||||
Processes environment observations into the LeRobot format by handling both images and states.
|
||||
|
||||
|
||||
@@ -805,7 +805,7 @@ class DataProcessorPipeline(ModelHubMixin, Generic[TOutput]):
|
||||
return transformed_transition[TransitionKey.COMPLEMENTARY_DATA]
|
||||
|
||||
|
||||
class ObservationProcessor(ProcessorStep, ABC):
|
||||
class ObservationProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the observation component of a transition.
|
||||
|
||||
Subclasses should override the `observation` method to implement custom observation processing.
|
||||
@@ -851,7 +851,7 @@ class ObservationProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class ActionProcessor(ProcessorStep, ABC):
|
||||
class ActionProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the action component of a transition.
|
||||
|
||||
Subclasses should override the `action` method to implement custom action processing.
|
||||
@@ -898,7 +898,7 @@ class ActionProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class RewardProcessor(ProcessorStep, ABC):
|
||||
class RewardProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the reward component of a transition.
|
||||
|
||||
Subclasses should override the `reward` method to implement custom reward processing.
|
||||
@@ -944,7 +944,7 @@ class RewardProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class DoneProcessor(ProcessorStep, ABC):
|
||||
class DoneProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the done flag of a transition.
|
||||
|
||||
Subclasses should override the `done` method to implement custom done flag processing.
|
||||
@@ -995,7 +995,7 @@ class DoneProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class TruncatedProcessor(ProcessorStep, ABC):
|
||||
class TruncatedProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the truncated flag of a transition.
|
||||
|
||||
Subclasses should override the `truncated` method to implement custom truncated flag processing.
|
||||
@@ -1042,7 +1042,7 @@ class TruncatedProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class InfoProcessor(ProcessorStep, ABC):
|
||||
class InfoProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the info dictionary of a transition.
|
||||
|
||||
Subclasses should override the `info` method to implement custom info processing.
|
||||
@@ -1094,7 +1094,7 @@ class InfoProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class ComplementaryDataProcessor(ProcessorStep, ABC):
|
||||
class ComplementaryDataProcessorStep(ProcessorStep, ABC):
|
||||
"""Base class for processors that modify only the complementary data of a transition.
|
||||
|
||||
Subclasses should override the `complementary_data` method to implement custom complementary data processing.
|
||||
@@ -1127,7 +1127,7 @@ class ComplementaryDataProcessor(ProcessorStep, ABC):
|
||||
return new_transition
|
||||
|
||||
|
||||
class IdentityProcessor(ProcessorStep):
|
||||
class IdentityProcessorStep(ProcessorStep):
|
||||
"""Identity processor that does nothing."""
|
||||
|
||||
def __call__(self, transition: EnvTransition) -> EnvTransition:
|
||||
|
||||
@@ -19,12 +19,12 @@ from typing import Any
|
||||
|
||||
from lerobot.configs.types import PolicyFeature
|
||||
|
||||
from .pipeline import ObservationProcessor, ProcessorStepRegistry
|
||||
from .pipeline import ObservationProcessorStep, ProcessorStepRegistry
|
||||
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register(name="rename_processor")
|
||||
class RenameProcessor(ObservationProcessor):
|
||||
class RenameProcessor(ObservationProcessorStep):
|
||||
"""Rename processor that renames keys in the observation."""
|
||||
|
||||
rename_map: dict[str, str] = field(default_factory=dict)
|
||||
|
||||
@@ -14,7 +14,7 @@ from lerobot.constants import OBS_LANGUAGE_ATTENTION_MASK, OBS_LANGUAGE_TOKENS
|
||||
from lerobot.utils.import_utils import _transformers_available
|
||||
|
||||
from .core import EnvTransition, TransitionKey
|
||||
from .pipeline import ObservationProcessor, ProcessorStepRegistry
|
||||
from .pipeline import ObservationProcessorStep, ProcessorStepRegistry
|
||||
|
||||
if TYPE_CHECKING or _transformers_available:
|
||||
from transformers import AutoTokenizer
|
||||
@@ -24,7 +24,7 @@ else:
|
||||
|
||||
@dataclass
|
||||
@ProcessorStepRegistry.register(name="tokenizer_processor")
|
||||
class TokenizerProcessor(ObservationProcessor):
|
||||
class TokenizerProcessor(ObservationProcessorStep):
|
||||
"""Tokenizes text tasks in complementary data using a huggingface tokenizer.
|
||||
|
||||
This processor handles tokenization of task strings found in the complementary_data
|
||||
|
||||
@@ -76,7 +76,7 @@ from lerobot.datasets.utils import hw_to_dataset_features
|
||||
from lerobot.datasets.video_utils import VideoEncodingManager
|
||||
from lerobot.policies.factory import make_policy, make_pre_post_processors
|
||||
from lerobot.policies.pretrained import PreTrainedPolicy
|
||||
from lerobot.processor import DataProcessorPipeline, IdentityProcessor, TransitionKey
|
||||
from lerobot.processor import DataProcessorPipeline, IdentityProcessorStep, TransitionKey
|
||||
from lerobot.processor.converters import (
|
||||
to_output_robot_action,
|
||||
to_transition_robot_observation,
|
||||
@@ -245,13 +245,15 @@ def record_loop(
|
||||
display_data: bool = False,
|
||||
):
|
||||
teleop_action_processor = teleop_action_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()], to_transition=to_transition_teleop_action, to_output=lambda tr: tr
|
||||
steps=[IdentityProcessorStep()], to_transition=to_transition_teleop_action, to_output=lambda tr: tr
|
||||
)
|
||||
robot_action_processor = robot_action_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()], to_transition=lambda tr: tr, to_output=to_output_robot_action
|
||||
steps=[IdentityProcessorStep()], to_transition=lambda tr: tr, to_output=to_output_robot_action
|
||||
)
|
||||
robot_observation_processor = robot_observation_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()], to_transition=to_transition_robot_observation, to_output=lambda tr: tr
|
||||
steps=[IdentityProcessorStep()],
|
||||
to_transition=to_transition_robot_observation,
|
||||
to_output=lambda tr: tr,
|
||||
)
|
||||
|
||||
if dataset is not None and dataset.fps != fps:
|
||||
|
||||
@@ -47,7 +47,7 @@ from pprint import pformat
|
||||
|
||||
from lerobot.configs import parser
|
||||
from lerobot.datasets.lerobot_dataset import LeRobotDataset
|
||||
from lerobot.processor import DataProcessorPipeline, IdentityProcessor
|
||||
from lerobot.processor import DataProcessorPipeline, IdentityProcessorStep
|
||||
from lerobot.processor.converters import to_output_robot_action, to_transition_teleop_action
|
||||
from lerobot.robots import ( # noqa: F401
|
||||
Robot,
|
||||
@@ -95,7 +95,7 @@ def replay(cfg: ReplayConfig):
|
||||
|
||||
# Initialize robot action processor with default if not provided
|
||||
robot_action_processor = cfg.robot_action_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()],
|
||||
steps=[IdentityProcessorStep()],
|
||||
to_transition=to_transition_teleop_action,
|
||||
to_output=to_output_robot_action, # type: ignore[arg-type]
|
||||
)
|
||||
|
||||
@@ -23,10 +23,10 @@ from lerobot.configs.types import FeatureType, PolicyFeature
|
||||
from lerobot.constants import ACTION, OBS_STATE
|
||||
from lerobot.model.kinematics import RobotKinematics
|
||||
from lerobot.processor import (
|
||||
ActionProcessor,
|
||||
ComplementaryDataProcessor,
|
||||
ActionProcessorStep,
|
||||
ComplementaryDataProcessorStep,
|
||||
EnvTransition,
|
||||
ObservationProcessor,
|
||||
ObservationProcessorStep,
|
||||
ProcessorStep,
|
||||
ProcessorStepRegistry,
|
||||
TransitionKey,
|
||||
@@ -36,7 +36,7 @@ from lerobot.robots.robot import Robot
|
||||
|
||||
@ProcessorStepRegistry.register("ee_reference_and_delta")
|
||||
@dataclass
|
||||
class EEReferenceAndDelta(ActionProcessor):
|
||||
class EEReferenceAndDelta(ActionProcessorStep):
|
||||
"""
|
||||
Compute the desired end-effector pose from the target pose and the current pose.
|
||||
|
||||
@@ -159,7 +159,7 @@ class EEReferenceAndDelta(ActionProcessor):
|
||||
|
||||
@ProcessorStepRegistry.register("ee_bounds_and_safety")
|
||||
@dataclass
|
||||
class EEBoundsAndSafety(ActionProcessor):
|
||||
class EEBoundsAndSafety(ActionProcessorStep):
|
||||
"""
|
||||
Clip the end-effector pose to the bounds and check for jumps.
|
||||
|
||||
@@ -389,7 +389,7 @@ class GripperVelocityToJoint(ProcessorStep):
|
||||
|
||||
@ProcessorStepRegistry.register("forward_kinematics_joints_to_ee")
|
||||
@dataclass
|
||||
class ForwardKinematicsJointsToEE(ObservationProcessor):
|
||||
class ForwardKinematicsJointsToEE(ObservationProcessorStep):
|
||||
"""
|
||||
Compute the end-effector pose from the joint positions.
|
||||
|
||||
@@ -433,7 +433,7 @@ class ForwardKinematicsJointsToEE(ObservationProcessor):
|
||||
|
||||
@ProcessorStepRegistry.register("add_robot_observation")
|
||||
@dataclass
|
||||
class AddRobotObservationAsComplimentaryData(ComplementaryDataProcessor):
|
||||
class AddRobotObservationAsComplimentaryData(ComplementaryDataProcessorStep):
|
||||
"""
|
||||
Read the robot's current observation and insert it into the transition as complementary data.
|
||||
|
||||
|
||||
@@ -61,7 +61,7 @@ import rerun as rr
|
||||
from lerobot.cameras.opencv.configuration_opencv import OpenCVCameraConfig # noqa: F401
|
||||
from lerobot.cameras.realsense.configuration_realsense import RealSenseCameraConfig # noqa: F401
|
||||
from lerobot.configs import parser
|
||||
from lerobot.processor import DataProcessorPipeline, IdentityProcessor
|
||||
from lerobot.processor import DataProcessorPipeline, IdentityProcessorStep
|
||||
from lerobot.processor.converters import (
|
||||
to_output_robot_action,
|
||||
to_transition_robot_observation,
|
||||
@@ -121,15 +121,17 @@ def teleop_loop(
|
||||
):
|
||||
# Initialize processors with defaults if not provided
|
||||
teleop_action_processor = teleop_action_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()], to_transition=to_transition_teleop_action, to_output=lambda tr: tr
|
||||
steps=[IdentityProcessorStep()], to_transition=to_transition_teleop_action, to_output=lambda tr: tr
|
||||
)
|
||||
robot_action_processor = robot_action_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()],
|
||||
steps=[IdentityProcessorStep()],
|
||||
to_transition=lambda tr: tr,
|
||||
to_output=to_output_robot_action, # type: ignore[arg-type]
|
||||
)
|
||||
robot_observation_processor = robot_observation_processor or DataProcessorPipeline(
|
||||
steps=[IdentityProcessor()], to_transition=to_transition_robot_observation, to_output=lambda tr: tr
|
||||
steps=[IdentityProcessorStep()],
|
||||
to_transition=to_transition_robot_observation,
|
||||
to_output=lambda tr: tr,
|
||||
)
|
||||
|
||||
# Reset processors
|
||||
|
||||
@@ -18,13 +18,13 @@ from dataclasses import dataclass, field
|
||||
|
||||
from lerobot.configs.types import FeatureType, PolicyFeature
|
||||
from lerobot.constants import ACTION
|
||||
from lerobot.processor import ActionProcessor, ProcessorStepRegistry
|
||||
from lerobot.processor import ActionProcessorStep, ProcessorStepRegistry
|
||||
from lerobot.teleoperators.phone.config_phone import PhoneOS
|
||||
|
||||
|
||||
@ProcessorStepRegistry.register("map_phone_action_to_robot_action")
|
||||
@dataclass
|
||||
class MapPhoneActionToRobotAction(ActionProcessor):
|
||||
class MapPhoneActionToRobotAction(ActionProcessorStep):
|
||||
"""
|
||||
Map calibrated phone pose (actions) to the inputs for robot actions
|
||||
|
||||
|
||||
@@ -27,7 +27,7 @@ from lerobot.policies.sac.reward_model.processor_classifier import make_classifi
|
||||
from lerobot.processor import (
|
||||
DataProcessorPipeline,
|
||||
DeviceProcessor,
|
||||
IdentityProcessor,
|
||||
IdentityProcessorStep,
|
||||
NormalizerProcessor,
|
||||
TransitionKey,
|
||||
)
|
||||
@@ -94,7 +94,7 @@ def test_make_classifier_processor_basic():
|
||||
# Check steps in postprocessor
|
||||
assert len(postprocessor.steps) == 2
|
||||
assert isinstance(postprocessor.steps[0], DeviceProcessor)
|
||||
assert isinstance(postprocessor.steps[1], IdentityProcessor)
|
||||
assert isinstance(postprocessor.steps[1], IdentityProcessorStep)
|
||||
|
||||
|
||||
def test_classifier_processor_normalization():
|
||||
|
||||
@@ -22,7 +22,7 @@ import torch
|
||||
from lerobot.configs.types import FeatureType, NormalizationMode, PolicyFeature
|
||||
from lerobot.processor import (
|
||||
DataProcessorPipeline,
|
||||
IdentityProcessor,
|
||||
IdentityProcessorStep,
|
||||
NormalizerProcessor,
|
||||
TransitionKey,
|
||||
UnnormalizerProcessor,
|
||||
@@ -1008,7 +1008,7 @@ def test_hotswap_stats_basic_functionality():
|
||||
# Create processors
|
||||
normalizer = NormalizerProcessor(features=features, norm_map=norm_map, stats=initial_stats)
|
||||
unnormalizer = UnnormalizerProcessor(features=features, norm_map=norm_map, stats=initial_stats)
|
||||
identity = IdentityProcessor()
|
||||
identity = IdentityProcessorStep()
|
||||
|
||||
# Create robot processor
|
||||
robot_processor = DataProcessorPipeline(steps=[normalizer, unnormalizer, identity])
|
||||
@@ -1089,7 +1089,7 @@ def test_hotswap_stats_only_affects_normalizer_steps():
|
||||
# Create mixed steps
|
||||
normalizer = NormalizerProcessor(features=features, norm_map=norm_map, stats=stats)
|
||||
unnormalizer = UnnormalizerProcessor(features=features, norm_map=norm_map, stats=stats)
|
||||
identity = IdentityProcessor()
|
||||
identity = IdentityProcessorStep()
|
||||
|
||||
robot_processor = DataProcessorPipeline(steps=[normalizer, identity, unnormalizer])
|
||||
|
||||
@@ -1135,7 +1135,7 @@ def test_hotswap_stats_no_normalizer_steps():
|
||||
}
|
||||
|
||||
# Create processor with only identity steps
|
||||
robot_processor = DataProcessorPipeline(steps=[IdentityProcessor(), IdentityProcessor()])
|
||||
robot_processor = DataProcessorPipeline(steps=[IdentityProcessorStep(), IdentityProcessorStep()])
|
||||
|
||||
# Hotswap stats - should work without error
|
||||
new_processor = hotswap_stats(robot_processor, stats)
|
||||
|
||||
Reference in New Issue
Block a user