Fix/earth rover dataset features (#3088)

* docs(earthrover): update EarthRover Mini Plus dataset features and descriptions

* refactor(teleop): rename rover action keys to linear_velocity/angular_velocity

* fix(earthrover): align observation and action features with frodobots/berkeley-frodobots-lerobot-7k

* chore: address PR review comments

* ci: retrigger checks
This commit is contained in:
Khalil Meftah
2026-03-17 18:33:53 +01:00
committed by GitHub
parent d90e4bcfd3
commit d9ec3a6fa2
3 changed files with 178 additions and 82 deletions
+11 -7
View File
@@ -204,22 +204,26 @@ Replace `your_username/dataset_name` with your Hugging Face username and a name
Your dataset includes: Your dataset includes:
**Your Actions (2 things)**: **Your Actions (2 features)**:
- How much you moved forward/backward - `linear_velocity`: How much you moved forward/backward
- How much you turned left/right - `angular_velocity`: How much you turned left/right
**Robot Observations (12 things)**: **Robot Observations (24 features)**:
- Front camera video - Front camera video
- Rear camera video - Rear camera video
- Current speed - Current speed
- Battery level - Battery level
- Which way the robot is facing - Orientation
- GPS location (latitude, longitude, signal strength) - GPS (latitude, longitude, signal strength)
- Network signal strength - Network signal strength
- Vibration level - Vibration level
- Lamp status (on/off) - Lamp state (on/off)
- Accelerometer (x, y, z)
- Gyroscope (x, y, z)
- Magnetometer (x, y, z)
- Wheel RPMs (4 wheels)
### Where Your Data Goes ### Where Your Data Goes
@@ -33,21 +33,40 @@ from .config_earthrover_mini_plus import EarthRoverMiniPlusConfig
logger = logging.getLogger(__name__) logger = logging.getLogger(__name__)
# Action feature keys # Action feature keys
ACTION_LINEAR_VEL = "linear.vel" ACTION_LINEAR_VEL = "linear_velocity"
ACTION_ANGULAR_VEL = "angular.vel" ACTION_ANGULAR_VEL = "angular_velocity"
# Observation feature keys # Observation feature keys — cameras
OBS_FRONT = "front" OBS_FRONT = "front"
OBS_REAR = "rear" OBS_REAR = "rear"
OBS_LINEAR_VEL = "linear.vel"
OBS_BATTERY_LEVEL = "battery.level" # Observation feature keys — telemetry
OBS_ORIENTATION_DEG = "orientation.deg" OBS_SPEED = "speed"
OBS_GPS_LATITUDE = "gps.latitude" OBS_BATTERY_LEVEL = "battery_level"
OBS_GPS_LONGITUDE = "gps.longitude" OBS_ORIENTATION = "orientation"
OBS_GPS_SIGNAL = "gps.signal" OBS_GPS_LATITUDE = "gps_latitude"
OBS_SIGNAL_LEVEL = "signal.level" OBS_GPS_LONGITUDE = "gps_longitude"
OBS_GPS_SIGNAL = "gps_signal"
OBS_SIGNAL_LEVEL = "signal_level"
OBS_VIBRATION = "vibration" OBS_VIBRATION = "vibration"
OBS_LAMP_STATE = "lamp.state" OBS_LAMP = "lamp"
# Observation feature keys — IMU sensors
OBS_ACCELEROMETER_X = "accelerometer_x"
OBS_ACCELEROMETER_Y = "accelerometer_y"
OBS_ACCELEROMETER_Z = "accelerometer_z"
OBS_GYROSCOPE_X = "gyroscope_x"
OBS_GYROSCOPE_Y = "gyroscope_y"
OBS_GYROSCOPE_Z = "gyroscope_z"
OBS_MAGNETOMETER_X = "magnetometer_filtered_x"
OBS_MAGNETOMETER_Y = "magnetometer_filtered_y"
OBS_MAGNETOMETER_Z = "magnetometer_filtered_z"
# Observation feature keys — wheel RPMs
OBS_WHEEL_RPM_0 = "wheel_rpm_0"
OBS_WHEEL_RPM_1 = "wheel_rpm_1"
OBS_WHEEL_RPM_2 = "wheel_rpm_2"
OBS_WHEEL_RPM_3 = "wheel_rpm_3"
class EarthRoverMiniPlus(Robot): class EarthRoverMiniPlus(Robot):
@@ -154,33 +173,60 @@ class EarthRoverMiniPlus(Robot):
dict: Observation features with types/shapes: dict: Observation features with types/shapes:
- front: (480, 640, 3) - Front camera RGB image - front: (480, 640, 3) - Front camera RGB image
- rear: (480, 640, 3) - Rear camera RGB image - rear: (480, 640, 3) - Rear camera RGB image
- linear.vel: float - Current speed (0-1, SDK reports only positive speeds) - speed: float - Current speed (raw SDK value)
- battery.level: float - Battery level (0-1, normalized from 0-100) - battery_level: float - Battery level (0-100)
- orientation.deg: float - Robot orientation (0-1, normalized from raw value) - orientation: float - Robot orientation in degrees
- gps.latitude: float - GPS latitude coordinate - gps_latitude: float - GPS latitude coordinate
- gps.longitude: float - GPS longitude coordinate - gps_longitude: float - GPS longitude coordinate
- gps.signal: float - GPS signal strength (0-1, normalized from percentage) - gps_signal: float - GPS signal strength (percentage)
- signal.level: float - Network signal level (0-1, normalized from 0-5) - signal_level: float - Network signal level (0-5)
- vibration: float - Vibration sensor reading - vibration: float - Vibration sensor reading
- lamp.state: float - Lamp state (0=off, 1=on) - lamp: float - Lamp state (0=off, 1=on)
- accelerometer_x: float - Accelerometer X axis (raw SDK value)
- accelerometer_y: float - Accelerometer Y axis (raw SDK value)
- accelerometer_z: float - Accelerometer Z axis (raw SDK value)
- gyroscope_x: float - Gyroscope X axis (raw SDK value)
- gyroscope_y: float - Gyroscope Y axis (raw SDK value)
- gyroscope_z: float - Gyroscope Z axis (raw SDK value)
- magnetometer_filtered_x: float - Magnetometer X axis (raw SDK value)
- magnetometer_filtered_y: float - Magnetometer Y axis (raw SDK value)
- magnetometer_filtered_z: float - Magnetometer Z axis (raw SDK value)
- wheel_rpm_0: float - Wheel 0 RPM
- wheel_rpm_1: float - Wheel 1 RPM
- wheel_rpm_2: float - Wheel 2 RPM
- wheel_rpm_3: float - Wheel 3 RPM
""" """
return { return {
# Cameras (height, width, channels) # Cameras (height, width, channels)
OBS_FRONT: (480, 640, 3), OBS_FRONT: (480, 640, 3),
OBS_REAR: (480, 640, 3), OBS_REAR: (480, 640, 3),
# Motion state # Telemetry
OBS_LINEAR_VEL: float, OBS_SPEED: float,
# Robot state
OBS_BATTERY_LEVEL: float, OBS_BATTERY_LEVEL: float,
OBS_ORIENTATION_DEG: float, OBS_ORIENTATION: float,
# GPS
OBS_GPS_LATITUDE: float, OBS_GPS_LATITUDE: float,
OBS_GPS_LONGITUDE: float, OBS_GPS_LONGITUDE: float,
OBS_GPS_SIGNAL: float, OBS_GPS_SIGNAL: float,
# Sensors
OBS_SIGNAL_LEVEL: float, OBS_SIGNAL_LEVEL: float,
OBS_VIBRATION: float, OBS_VIBRATION: float,
OBS_LAMP_STATE: float, OBS_LAMP: float,
# IMU — accelerometer
OBS_ACCELEROMETER_X: float,
OBS_ACCELEROMETER_Y: float,
OBS_ACCELEROMETER_Z: float,
# IMU — gyroscope
OBS_GYROSCOPE_X: float,
OBS_GYROSCOPE_Y: float,
OBS_GYROSCOPE_Z: float,
# IMU — magnetometer
OBS_MAGNETOMETER_X: float,
OBS_MAGNETOMETER_Y: float,
OBS_MAGNETOMETER_Z: float,
# Wheel RPMs
OBS_WHEEL_RPM_0: float,
OBS_WHEEL_RPM_1: float,
OBS_WHEEL_RPM_2: float,
OBS_WHEEL_RPM_3: float,
} }
@cached_property @cached_property
@@ -189,8 +235,8 @@ class EarthRoverMiniPlus(Robot):
Returns: Returns:
dict: Action features with types: dict: Action features with types:
- linear.vel: float - Target linear velocity - linear_velocity: float - Target linear velocity (-1 to 1)
- angular.vel: float - Target angular velocity - angular_velocity: float - Target angular velocity (-1 to 1)
""" """
return { return {
ACTION_LINEAR_VEL: float, ACTION_LINEAR_VEL: float,
@@ -201,19 +247,29 @@ class EarthRoverMiniPlus(Robot):
def get_observation(self) -> RobotObservation: def get_observation(self) -> RobotObservation:
"""Get current robot observation from SDK. """Get current robot observation from SDK.
Camera frames are retrieved from SDK endpoints /v2/front and /v2/rear.
Frames are decoded from base64 and converted from BGR to RGB format.
Robot telemetry is retrieved from /data endpoint.
Sensor arrays (accels, gyros, mags, rpms) each contain entries of
[values..., timestamp]; the latest reading from each array is used.
Returns: Returns:
RobotObservation: Observation containing: RobotObservation: Observation containing:
- front: Front camera image (480, 640, 3) in RGB format - front: Front camera image (480, 640, 3) in RGB format
- rear: Rear camera image (480, 640, 3) in RGB format - rear: Rear camera image (480, 640, 3) in RGB format
- linear.vel: Current speed (0-1, SDK reports only positive speeds) - speed: float - Current speed (raw SDK value)
- battery.level: Battery level (0-1, normalized from 0-100) - battery_level: float - Battery level (0-100)
- orientation.deg: Robot orientation (0-1, normalized from raw value) - orientation: float - Robot orientation in degrees
- gps.latitude: GPS latitude coordinate - gps_latitude: float - GPS latitude coordinate
- gps.longitude: GPS longitude coordinate - gps_longitude: float - GPS longitude coordinate
- gps.signal: GPS signal strength (0-1, normalized from percentage) - gps_signal: float - GPS signal strength (percentage)
- signal.level: Network signal level (0-1, normalized from 0-5) - signal_level: float - Network signal level (0-5)
- vibration: Vibration sensor reading - vibration: float - Vibration sensor reading
- lamp.state: Lamp state (0=off, 1=on) - lamp: float - Lamp state (0=off, 1=on)
- accelerometer_x/y/z: float - Accelerometer axes (raw SDK value)
- gyroscope_x/y/z: float - Gyroscope axes (raw SDK value)
- magnetometer_filtered_x/y/z: float - Magnetometer axes (raw SDK value)
- wheel_rpm_0/1/2/3: float - Wheel RPMs
Raises: Raises:
DeviceNotConnectedError: If robot is not connected DeviceNotConnectedError: If robot is not connected
@@ -235,22 +291,41 @@ class EarthRoverMiniPlus(Robot):
# Get robot state from SDK # Get robot state from SDK
robot_data = self._get_robot_data() robot_data = self._get_robot_data()
# Motion state # Telemetry
observation[OBS_LINEAR_VEL] = robot_data["speed"] / 100.0 # Normalize 0-100 to 0-1 observation[OBS_SPEED] = float(robot_data["speed"])
observation[OBS_BATTERY_LEVEL] = float(robot_data["battery"])
observation[OBS_ORIENTATION] = float(robot_data["orientation"])
observation[OBS_GPS_LATITUDE] = float(robot_data["latitude"])
observation[OBS_GPS_LONGITUDE] = float(robot_data["longitude"])
observation[OBS_GPS_SIGNAL] = float(robot_data["gps_signal"])
observation[OBS_SIGNAL_LEVEL] = float(robot_data["signal_level"])
observation[OBS_VIBRATION] = float(robot_data["vibration"])
observation[OBS_LAMP] = float(robot_data["lamp"])
# Robot state # Accelerometer — latest reading from accels array [x, y, z, ts]
observation[OBS_BATTERY_LEVEL] = robot_data["battery"] / 100.0 # Normalize 0-100 to 0-1 accel = self._latest_sensor_reading(robot_data, "accels", n_values=3)
observation[OBS_ORIENTATION_DEG] = robot_data["orientation"] / 360.0 # Normalize to 0-1 observation[OBS_ACCELEROMETER_X] = accel[0]
observation[OBS_ACCELEROMETER_Y] = accel[1]
observation[OBS_ACCELEROMETER_Z] = accel[2]
# GPS data # Gyroscope — latest reading from gyros array [x, y, z, ts]
observation[OBS_GPS_LATITUDE] = robot_data["latitude"] gyro = self._latest_sensor_reading(robot_data, "gyros", n_values=3)
observation[OBS_GPS_LONGITUDE] = robot_data["longitude"] observation[OBS_GYROSCOPE_X] = gyro[0]
observation[OBS_GPS_SIGNAL] = robot_data["gps_signal"] / 100.0 # Normalize percentage to 0-1 observation[OBS_GYROSCOPE_Y] = gyro[1]
observation[OBS_GYROSCOPE_Z] = gyro[2]
# Sensors # Magnetometer — latest reading from mags array [x, y, z, ts]
observation[OBS_SIGNAL_LEVEL] = robot_data["signal_level"] / 5.0 # Normalize 0-5 to 0-1 mag = self._latest_sensor_reading(robot_data, "mags", n_values=3)
observation[OBS_VIBRATION] = robot_data["vibration"] observation[OBS_MAGNETOMETER_X] = mag[0]
observation[OBS_LAMP_STATE] = float(robot_data["lamp"]) # 0 or 1 observation[OBS_MAGNETOMETER_Y] = mag[1]
observation[OBS_MAGNETOMETER_Z] = mag[2]
# Wheel RPMs — latest reading from rpms array [w0, w1, w2, w3, ts]
rpm = self._latest_sensor_reading(robot_data, "rpms", n_values=4)
observation[OBS_WHEEL_RPM_0] = rpm[0]
observation[OBS_WHEEL_RPM_1] = rpm[1]
observation[OBS_WHEEL_RPM_2] = rpm[2]
observation[OBS_WHEEL_RPM_3] = rpm[3]
return observation return observation
@@ -260,11 +335,12 @@ class EarthRoverMiniPlus(Robot):
Args: Args:
action: Action dict with keys: action: Action dict with keys:
- linear.vel: Target linear velocity (-1 to 1) - linear_velocity: Target linear velocity (-1 to 1)
- angular.vel: Target angular velocity (-1 to 1) - angular_velocity: Target angular velocity (-1 to 1)
Returns: Returns:
RobotAction: The action that was sent (matches action_features keys) RobotAction: The action that was sent (matches action_features keys)
Raises: Raises:
DeviceNotConnectedError: If robot is not connected DeviceNotConnectedError: If robot is not connected
@@ -272,18 +348,14 @@ class EarthRoverMiniPlus(Robot):
Actions are sent to SDK via POST /control endpoint. Actions are sent to SDK via POST /control endpoint.
SDK expects commands in range [-1, 1]. SDK expects commands in range [-1, 1].
""" """
# Extract action values and convert to float
linear = float(action.get(ACTION_LINEAR_VEL, 0.0)) linear = float(action.get(ACTION_LINEAR_VEL, 0.0))
angular = float(action.get(ACTION_ANGULAR_VEL, 0.0)) angular = float(action.get(ACTION_ANGULAR_VEL, 0.0))
# Send command to SDK
try: try:
self._send_command_to_sdk(linear, angular) self._send_command_to_sdk(linear, angular)
except Exception as e: except Exception as e:
logger.error(f"Error sending action: {e}") logger.error(f"Error sending action: {e}")
# Return action in format matching action_features
return { return {
ACTION_LINEAR_VEL: linear, ACTION_LINEAR_VEL: linear,
ACTION_ANGULAR_VEL: angular, ACTION_ANGULAR_VEL: angular,
@@ -394,11 +466,27 @@ class EarthRoverMiniPlus(Robot):
logger.error(f"Error decoding image: {e}") logger.error(f"Error decoding image: {e}")
return None return None
@staticmethod
def _latest_sensor_reading(robot_data: dict, key: str, n_values: int) -> list[float]:
"""Extract the latest sensor reading from an SDK sensor array.
The SDK returns sensor arrays like ``accels``, ``gyros``, ``mags``,
``rpms`` where each entry is ``[value_0, ..., value_n, timestamp]``.
This helper returns the *n_values* leading floats from the last entry,
falling back to zeros when the key is missing or the array is empty.
"""
readings = robot_data.get(key)
if readings and len(readings) > 0:
latest = readings[-1]
return [float(v) for v in latest[:n_values]]
return [0.0] * n_values
def _get_robot_data(self) -> dict: def _get_robot_data(self) -> dict:
"""Get robot telemetry data from SDK. """Get robot telemetry data from SDK.
Returns: Returns:
dict: Robot telemetry data including battery, speed, orientation, GPS, etc: dict: Robot telemetry data including battery, speed, orientation, GPS,
and sensor arrays (accels, gyros, mags, rpms):
- Current data (if request succeeds) - Current data (if request succeeds)
- Cached data (if request fails but cache exists) - Cached data (if request fails but cache exists)
- Default values (if request fails and no cache exists yet) - Default values (if request fails and no cache exists yet)
@@ -420,19 +508,23 @@ class EarthRoverMiniPlus(Robot):
# Fallback: use cache or default values # Fallback: use cache or default values
if self._last_robot_data is not None: if self._last_robot_data is not None:
return self._last_robot_data return self._last_robot_data
else:
# Return dict with default values (used only on first failure before any cache exists) # Return dict with default values (used only on first failure before any cache exists)
return { return {
"speed": 0, "speed": 0,
"battery": 0, "battery": 0,
"orientation": 0, "orientation": 0,
"latitude": 0.0, "latitude": 0.0,
"longitude": 0.0, "longitude": 0.0,
"gps_signal": 0, "gps_signal": 0,
"signal_level": 0, "signal_level": 0,
"vibration": 0.0, "vibration": 0.0,
"lamp": 0, "lamp": 0,
} "accels": [],
"gyros": [],
"mags": [],
"rpms": [],
}
def _send_command_to_sdk(self, linear: float, angular: float, lamp: int = 0) -> bool: def _send_command_to_sdk(self, linear: float, angular: float, lamp: int = 0) -> bool:
"""Send control command to SDK. """Send control command to SDK.
@@ -341,8 +341,8 @@ class KeyboardRoverTeleop(KeyboardTeleop):
def action_features(self) -> dict: def action_features(self) -> dict:
"""Return action format for rover (linear and angular velocities).""" """Return action format for rover (linear and angular velocities)."""
return { return {
"linear.vel": float, "linear_velocity": float,
"angular.vel": float, "angular_velocity": float,
} }
@property @property
@@ -366,7 +366,7 @@ class KeyboardRoverTeleop(KeyboardTeleop):
Get the current action based on pressed keys. Get the current action based on pressed keys.
Returns: Returns:
RobotAction with 'linear.vel' and 'angular.vel' keys RobotAction with 'linear_velocity' and 'angular_velocity' keys.
""" """
before_read_t = time.perf_counter() before_read_t = time.perf_counter()
@@ -427,6 +427,6 @@ class KeyboardRoverTeleop(KeyboardTeleop):
self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
return { return {
"linear.vel": linear_velocity, "linear_velocity": linear_velocity,
"angular.vel": angular_velocity, "angular_velocity": angular_velocity,
} }