mirror of
https://github.com/huggingface/lerobot.git
synced 2026-05-24 04:59:47 +00:00
also have pipeline for feedback_features and action_features
This commit is contained in:
@@ -106,7 +106,7 @@ class BiOpenArmFollower(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -90,7 +90,7 @@ class BiSOFollower(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -184,7 +184,7 @@ class EarthRoverMiniPlus(Robot):
|
||||
}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
"""Define the action space.
|
||||
|
||||
Returns:
|
||||
|
||||
@@ -75,7 +75,7 @@ class HopeJrArm(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -111,7 +111,7 @@ class HopeJrHand(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -77,7 +77,7 @@ class KochFollower(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -102,7 +102,7 @@ class LeKiwi(Robot):
|
||||
return {**self._state_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._state_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -102,7 +102,7 @@ class LeKiwiClient(Robot):
|
||||
return {**self._state_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._state_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -77,7 +77,7 @@ class OmxFollower(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -110,7 +110,7 @@ class OpenArmFollower(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
"""Action features."""
|
||||
return self._motors_ft
|
||||
|
||||
|
||||
@@ -99,7 +99,7 @@ class Reachy2Robot(Robot):
|
||||
return {**self.motors_features, **self.camera_features}
|
||||
|
||||
@property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self.motors_features
|
||||
|
||||
@property
|
||||
|
||||
@@ -168,23 +168,40 @@ class Robot(abc.ABC):
|
||||
|
||||
@property
|
||||
@abc.abstractmethod
|
||||
def action_features(self) -> dict:
|
||||
def raw_action_features(self) -> dict:
|
||||
"""
|
||||
A dictionary describing the structure and types of the actions expected by the robot.
|
||||
Its structure (keys) should match the structure of what is passed to
|
||||
:pymeth:`send_action`. Values for the dict should be the type of the value if it's
|
||||
a simple value, e.g. ``float`` for single proprioceptive value
|
||||
(a joint's goal position/velocity).
|
||||
Hardware-level action features (before any pipeline transformation).
|
||||
|
||||
For simple robots (no input pipeline), this returns motor-level features.
|
||||
For robots with an IK pipeline, override this to return the pipeline's input spec
|
||||
(e.g., EE features) so that compatibility checks work correctly.
|
||||
A dictionary describing the structure and types of the actions accepted directly
|
||||
by the robot hardware (i.e. what :pymeth:`_send_action` receives). Its structure
|
||||
(keys) should match the structure of what is expected by :pymeth:`_send_action`.
|
||||
Values should be the type of the value if it's a simple value, e.g. ``float`` for
|
||||
single proprioceptive value (a joint's goal position/velocity).
|
||||
|
||||
Note: this property should be able to be called regardless of whether the robot
|
||||
is connected or not.
|
||||
"""
|
||||
pass
|
||||
|
||||
@property
|
||||
def action_features(self) -> dict:
|
||||
"""
|
||||
Pipeline-transformed action features.
|
||||
|
||||
Applies input_pipeline().transform_features() to raw_action_features so the
|
||||
returned dict reflects what the input pipeline outputs to hardware.
|
||||
|
||||
Use raw_action_features to inspect hardware-level action feature shapes.
|
||||
|
||||
Note: this property should be able to be called regardless of whether the robot
|
||||
is connected or not.
|
||||
"""
|
||||
from lerobot.datasets.pipeline_features import create_initial_features # lazy import
|
||||
|
||||
initial = create_initial_features(action=self.raw_action_features)
|
||||
transformed = self.input_pipeline().transform_features(initial)
|
||||
return transformed.get(PipelineFeatureType.ACTION, {})
|
||||
|
||||
@property
|
||||
@abc.abstractmethod
|
||||
def is_connected(self) -> bool:
|
||||
|
||||
@@ -78,7 +78,7 @@ class SOFollower(Robot):
|
||||
return {**self._motors_ft, **self._cameras_ft}
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return self._motors_ft
|
||||
|
||||
@property
|
||||
|
||||
@@ -170,7 +170,7 @@ class UnitreeG1(Robot):
|
||||
time.sleep(sleep_time)
|
||||
|
||||
@cached_property
|
||||
def action_features(self) -> dict[str, type]:
|
||||
def raw_action_features(self) -> dict[str, type]:
|
||||
return {f"{G1_29_JointIndex(motor).name}.q": float for motor in G1_29_JointIndex}
|
||||
|
||||
def calibrate(self) -> None: # robot is already calibrated
|
||||
|
||||
@@ -82,7 +82,7 @@ class BiOpenArmLeader(Teleoperator):
|
||||
}
|
||||
|
||||
@cached_property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -65,7 +65,7 @@ class BiSOLeader(Teleoperator):
|
||||
}
|
||||
|
||||
@cached_property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -72,7 +72,7 @@ class GamepadTeleop(Teleoperator):
|
||||
}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict:
|
||||
def raw_feedback_features(self) -> dict:
|
||||
return {}
|
||||
|
||||
def connect(self) -> None:
|
||||
|
||||
@@ -85,7 +85,7 @@ class HomunculusArm(Teleoperator):
|
||||
return {f"{joint}.pos": float for joint in self.joints}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict:
|
||||
def raw_feedback_features(self) -> dict:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -111,7 +111,7 @@ class HomunculusGlove(Teleoperator):
|
||||
return {f"{joint}.pos": float for joint in self.joints}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict:
|
||||
def raw_feedback_features(self) -> dict:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -75,7 +75,7 @@ class KeyboardTeleop(Teleoperator):
|
||||
}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict:
|
||||
def raw_feedback_features(self) -> dict:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -62,7 +62,7 @@ class KochLeader(Teleoperator):
|
||||
return {f"{motor}.pos": float for motor in self.bus.motors}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -61,7 +61,7 @@ class OmxLeader(Teleoperator):
|
||||
return {f"{motor}.pos": float for motor in self.bus.motors}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -75,7 +75,7 @@ class OpenArmLeader(Teleoperator):
|
||||
return features
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
"""Feedback features (not implemented for OpenArms)."""
|
||||
return {}
|
||||
|
||||
|
||||
@@ -131,7 +131,7 @@ class OpenArmMini(Teleoperator):
|
||||
return features
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -56,9 +56,9 @@ class BasePhone:
|
||||
}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
# No haptic or other feedback implemented yet
|
||||
pass
|
||||
return {}
|
||||
|
||||
def configure(self) -> None:
|
||||
# No additional configuration required for phone teleop
|
||||
@@ -399,8 +399,8 @@ class Phone(Teleoperator):
|
||||
return self._phone_impl.raw_action_features
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
return self._phone_impl.feedback_features
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return self._phone_impl.raw_feedback_features
|
||||
|
||||
def configure(self) -> None:
|
||||
return self._phone_impl.configure()
|
||||
|
||||
@@ -120,7 +120,7 @@ class Reachy2Teleoperator(Teleoperator):
|
||||
return dict.fromkeys(self.joints_dict.keys(), float)
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -59,7 +59,7 @@ class SOLeader(Teleoperator):
|
||||
return {f"{motor}.pos": float for motor in self.bus.motors}
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -168,18 +168,42 @@ class Teleoperator(abc.ABC):
|
||||
|
||||
@property
|
||||
@abc.abstractmethod
|
||||
def feedback_features(self) -> dict:
|
||||
def raw_feedback_features(self) -> dict:
|
||||
"""
|
||||
A dictionary describing the structure and types of the feedback actions expected
|
||||
by the teleoperator. Its structure (keys) should match the structure of what is
|
||||
passed to :pymeth:`send_feedback`. Values should be the type of the value if it's
|
||||
a simple value, e.g. ``float`` for single proprioceptive value.
|
||||
Hardware-level feedback features (before any pipeline transformation).
|
||||
|
||||
A dictionary describing the structure and types of the feedback accepted directly
|
||||
by the teleoperator hardware (i.e. what :pymeth:`_send_feedback` receives). Its
|
||||
structure (keys) should match the structure of what is expected by
|
||||
:pymeth:`_send_feedback`. Values should be the type of the value if it's a simple
|
||||
value, e.g. ``float`` for single proprioceptive value.
|
||||
|
||||
Return an empty dict if this teleoperator does not support feedback.
|
||||
|
||||
Note: this property should be able to be called regardless of whether the
|
||||
teleoperator is connected or not.
|
||||
"""
|
||||
pass
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict:
|
||||
"""
|
||||
Pipeline-transformed feedback features.
|
||||
|
||||
Applies input_pipeline().transform_features() to raw_feedback_features so the
|
||||
returned dict reflects what the input pipeline outputs to the teleoperator hardware.
|
||||
|
||||
Use raw_feedback_features to inspect hardware-level feedback feature shapes.
|
||||
|
||||
Note: this property should be able to be called regardless of whether the
|
||||
teleoperator is connected or not.
|
||||
"""
|
||||
from lerobot.datasets.pipeline_features import create_initial_features # lazy import
|
||||
|
||||
initial = create_initial_features(observation=self.raw_feedback_features)
|
||||
transformed = self.input_pipeline().transform_features(initial)
|
||||
return transformed.get(PipelineFeatureType.OBSERVATION, {})
|
||||
|
||||
@property
|
||||
@abc.abstractmethod
|
||||
def is_connected(self) -> bool:
|
||||
|
||||
@@ -76,7 +76,7 @@ class UnitreeG1Teleoperator(Teleoperator):
|
||||
return {f"{name}.q": float for name in self._g1_joint_names}
|
||||
|
||||
@cached_property
|
||||
def feedback_features(self) -> dict[str, type]:
|
||||
def raw_feedback_features(self) -> dict[str, type]:
|
||||
return {}
|
||||
|
||||
@property
|
||||
|
||||
@@ -100,7 +100,7 @@ class MockRobot(Robot):
|
||||
return {**_JOINT_FEATURES, "camera": (480, 640, 3)}
|
||||
|
||||
@property
|
||||
def action_features(self) -> dict:
|
||||
def raw_action_features(self) -> dict:
|
||||
return _JOINT_FEATURES
|
||||
|
||||
@property
|
||||
@@ -147,7 +147,7 @@ class MockTeleop(Teleoperator):
|
||||
return _JOINT_FEATURES
|
||||
|
||||
@property
|
||||
def feedback_features(self) -> dict:
|
||||
def raw_feedback_features(self) -> dict:
|
||||
return {}
|
||||
|
||||
@property
|
||||
@@ -268,6 +268,24 @@ def test_robot_raw_observation_features_unchanged_after_pipeline():
|
||||
assert "camera" in raw
|
||||
|
||||
|
||||
def test_robot_action_features_identity_matches_raw():
|
||||
"""action_features equals raw_action_features with identity input pipeline."""
|
||||
robot = MockRobot()
|
||||
assert robot.action_features == robot.raw_action_features
|
||||
|
||||
|
||||
def test_robot_raw_action_features_unchanged_after_pipeline():
|
||||
"""raw_action_features is unaffected by any pipeline."""
|
||||
robot = MockRobot()
|
||||
double_pipeline = RobotProcessorPipeline[tuple[RobotAction, RobotObservation], RobotAction](
|
||||
steps=[DoubleActionStep()],
|
||||
to_transition=robot_action_observation_to_transition,
|
||||
to_output=transition_to_robot_action,
|
||||
)
|
||||
robot.set_input_pipeline(double_pipeline)
|
||||
assert robot.raw_action_features == _JOINT_FEATURES
|
||||
|
||||
|
||||
def test_robot_set_output_pipeline_replaces_identity():
|
||||
"""set_output_pipeline replaces the default identity."""
|
||||
robot = MockRobot()
|
||||
@@ -300,6 +318,18 @@ def test_teleop_action_features_identity_matches_raw():
|
||||
assert teleop.action_features == teleop.raw_action_features
|
||||
|
||||
|
||||
def test_teleop_feedback_features_identity_matches_raw():
|
||||
"""feedback_features equals raw_feedback_features with identity input pipeline."""
|
||||
teleop = MockTeleop()
|
||||
assert teleop.feedback_features == teleop.raw_feedback_features
|
||||
|
||||
|
||||
def test_teleop_feedback_features_empty_when_raw_empty():
|
||||
"""feedback_features returns empty dict when raw_feedback_features is empty."""
|
||||
teleop = MockTeleop()
|
||||
assert teleop.feedback_features == {}
|
||||
|
||||
|
||||
def test_teleop_set_output_pipeline():
|
||||
teleop = MockTeleop()
|
||||
p = _make_identity_teleop_action_pipeline()
|
||||
|
||||
Reference in New Issue
Block a user