704 lines
31 KiB
Python
704 lines
31 KiB
Python
import json
|
|
import logging
|
|
import time
|
|
import warnings
|
|
from dataclasses import dataclass, field, replace
|
|
from pathlib import Path
|
|
from typing import Sequence
|
|
|
|
import numpy as np
|
|
import torch
|
|
|
|
from lerobot.common.robot_devices.cameras.utils import Camera
|
|
from lerobot.common.robot_devices.motors.dynamixel import (
|
|
CalibrationMode,
|
|
TorqueMode,
|
|
convert_degrees_to_steps,
|
|
)
|
|
from lerobot.common.robot_devices.motors.utils import MotorsBus
|
|
from lerobot.common.robot_devices.robots.utils import get_arm_id
|
|
from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError
|
|
|
|
########################################################################
|
|
# Calibration logic
|
|
########################################################################
|
|
|
|
URL_TEMPLATE = (
|
|
"https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
|
|
)
|
|
|
|
# The following positions are provided in nominal degree range ]-180, +180[
|
|
# For more info on these constants, see comments in the code where they get used.
|
|
ZERO_POSITION_DEGREE = 0
|
|
ROTATED_POSITION_DEGREE = 90
|
|
|
|
|
|
def assert_drive_mode(drive_mode):
|
|
# `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted.
|
|
if not np.all(np.isin(drive_mode, [0, 1])):
|
|
raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})")
|
|
|
|
|
|
def apply_drive_mode(position, drive_mode):
|
|
assert_drive_mode(drive_mode)
|
|
# Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted,
|
|
# to [-1, 1] with 1 indicates original rotation direction and -1 inverted.
|
|
signed_drive_mode = -(drive_mode * 2 - 1)
|
|
position *= signed_drive_mode
|
|
return position
|
|
|
|
|
|
def compute_nearest_rounded_position(position, models):
|
|
delta_turn = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, models)
|
|
nearest_pos = np.round(position.astype(float) / delta_turn) * delta_turn
|
|
return nearest_pos.astype(position.dtype)
|
|
|
|
|
|
def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
|
|
"""This function ensures that a neural network trained on data collected on a given robot
|
|
can work on another robot. For instance before calibration, setting a same goal position
|
|
for each motor of two different robots will get two very different positions. But after calibration,
|
|
the two robots will move to the same position.To this end, this function computes the homing offset
|
|
and the drive mode for each motor of a given robot.
|
|
|
|
Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps
|
|
to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions
|
|
being 0. During the calibration process, you will need to manually move the robot to this "zero position".
|
|
|
|
Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled
|
|
in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot
|
|
to the "rotated position".
|
|
|
|
After calibration, the homing offsets and drive modes are stored in a cache.
|
|
|
|
Example of usage:
|
|
```python
|
|
run_arm_calibration(arm, "koch", "left", "follower")
|
|
```
|
|
"""
|
|
if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
|
|
raise ValueError("To run calibration, the torque must be disabled on all motors.")
|
|
|
|
print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
|
|
|
|
print("\nMove arm to zero position")
|
|
print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero"))
|
|
input("Press Enter to continue...")
|
|
|
|
# We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed.
|
|
# It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will
|
|
# correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position.
|
|
zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models)
|
|
|
|
# Compute homing offset so that `present_position + homing_offset ~= target_position`.
|
|
zero_pos = arm.read("Present_Position")
|
|
zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.motor_models)
|
|
homing_offset = zero_target_pos - zero_nearest_pos
|
|
|
|
# The rotated target position corresponds to a rotation of a quarter turn from the zero position.
|
|
# This allows to identify the rotation direction of each motor.
|
|
# For instance, if the motor rotates 90 degree, and its value is -90 after applying the homing offset, then we know its rotation direction
|
|
# is inverted. However, for the calibration being successful, we need everyone to follow the same target position.
|
|
# Sometimes, there is only one possible rotation direction. For instance, if the gripper is closed, there is only one direction which
|
|
# corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarely rotate clockwise from the point of view
|
|
# of the previous motor in the kinetic chain.
|
|
print("\nMove arm to rotated target position")
|
|
print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated"))
|
|
input("Press Enter to continue...")
|
|
|
|
rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models)
|
|
|
|
# Find drive mode by rotating each motor by a quarter of a turn.
|
|
# Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0).
|
|
rotated_pos = arm.read("Present_Position")
|
|
drive_mode = (rotated_pos < zero_pos).astype(np.int32)
|
|
|
|
# Re-compute homing offset to take into account drive mode
|
|
rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode)
|
|
rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.motor_models)
|
|
homing_offset = rotated_target_pos - rotated_nearest_pos
|
|
|
|
print("\nMove arm to rest position")
|
|
print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest"))
|
|
input("Press Enter to continue...")
|
|
print()
|
|
|
|
# Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
|
|
calib_mode = [CalibrationMode.DEGREE.name] * len(arm.motor_names)
|
|
|
|
# TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml?
|
|
if robot_type == "aloha" and "gripper" in arm.motor_names:
|
|
# Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100]
|
|
calib_idx = arm.motor_names.index("gripper")
|
|
calib_mode[calib_idx] = CalibrationMode.LINEAR.name
|
|
|
|
calib_data = {
|
|
"homing_offset": homing_offset.tolist(),
|
|
"drive_mode": drive_mode.tolist(),
|
|
"start_pos": zero_pos.tolist(),
|
|
"end_pos": rotated_pos.tolist(),
|
|
"calib_mode": calib_mode,
|
|
"motor_names": arm.motor_names,
|
|
}
|
|
return calib_data
|
|
|
|
|
|
def ensure_safe_goal_position(
|
|
goal_pos: torch.Tensor, present_pos: torch.Tensor, max_relative_target: float | list[float]
|
|
):
|
|
# Cap relative action target magnitude for safety.
|
|
diff = goal_pos - present_pos
|
|
max_relative_target = torch.tensor(max_relative_target)
|
|
safe_diff = torch.minimum(diff, max_relative_target)
|
|
safe_diff = torch.maximum(safe_diff, -max_relative_target)
|
|
safe_goal_pos = present_pos + safe_diff
|
|
|
|
if not torch.allclose(goal_pos, safe_goal_pos):
|
|
logging.warning(
|
|
"Relative goal position magnitude had to be clamped to be safe.\n"
|
|
f" requested relative goal position target: {diff}\n"
|
|
f" clamped relative goal position target: {safe_diff}"
|
|
)
|
|
|
|
return safe_goal_pos
|
|
|
|
|
|
########################################################################
|
|
# Manipulator robot
|
|
########################################################################
|
|
|
|
|
|
@dataclass
|
|
class ManipulatorRobotConfig:
|
|
"""
|
|
Example of usage:
|
|
```python
|
|
ManipulatorRobotConfig()
|
|
```
|
|
"""
|
|
|
|
# Define all components of the robot
|
|
robot_type: str | None = None
|
|
leader_arms: dict[str, MotorsBus] = field(default_factory=lambda: {})
|
|
follower_arms: dict[str, MotorsBus] = field(default_factory=lambda: {})
|
|
cameras: dict[str, Camera] = field(default_factory=lambda: {})
|
|
|
|
# Optionally limit the magnitude of the relative positional target vector for safety purposes.
|
|
# Set this to a positive scalar to have the same value for all motors, or a list that is the same length
|
|
# as the number of motors in your follower arms (assumes all follower arms have the same number of
|
|
# motors).
|
|
max_relative_target: list[float] | float | None = None
|
|
|
|
# Optionally set the leader arm in torque mode with the gripper motor set to this angle. This makes it
|
|
# possible to squeeze the gripper and have it spring back to an open position on its own. If None, the
|
|
# gripper is not put in torque mode.
|
|
gripper_open_degree: float | None = None
|
|
|
|
def __setattr__(self, prop: str, val):
|
|
if prop == "max_relative_target" and val is not None and isinstance(val, Sequence):
|
|
for name in self.follower_arms:
|
|
if len(self.follower_arms[name].motors) != len(val):
|
|
raise ValueError(
|
|
f"len(max_relative_target)={len(val)} but the follower arm with name {name} has "
|
|
f"{len(self.follower_arms[name].motors)} motors. Please make sure that the "
|
|
f"`max_relative_target` list has as many parameters as there are motors per arm. "
|
|
"Note: This feature does not yet work with robots where different follower arms have "
|
|
"different numbers of motors."
|
|
)
|
|
super().__setattr__(prop, val)
|
|
|
|
|
|
class ManipulatorRobot:
|
|
# TODO(rcadene): Implement force feedback
|
|
"""This class allows to control any manipulator robot of various number of motors.
|
|
|
|
Non exaustive list of robots:
|
|
- [Koch v1.0](https://github.com/AlexanderKoch-Koch/low_cost_robot), with and without the wrist-to-elbow expansion, developed
|
|
by Alexander Koch from [Tau Robotics](https://tau-robotics.com)
|
|
- [Koch v1.1](https://github.com/jess-moss/koch-v1-1) developed by Jess Moss
|
|
- [Aloha](https://www.trossenrobotics.com/aloha-kits) developed by Trossen Robotics
|
|
|
|
Example of highest frequency teleoperation without camera:
|
|
```python
|
|
# Defines how to communicate with the motors of the leader and follower arms
|
|
leader_arms = {
|
|
"main": DynamixelMotorsBus(
|
|
port="/dev/tty.usbmodem575E0031751",
|
|
motors={
|
|
# name: (index, model)
|
|
"shoulder_pan": (1, "xl330-m077"),
|
|
"shoulder_lift": (2, "xl330-m077"),
|
|
"elbow_flex": (3, "xl330-m077"),
|
|
"wrist_flex": (4, "xl330-m077"),
|
|
"wrist_roll": (5, "xl330-m077"),
|
|
"gripper": (6, "xl330-m077"),
|
|
},
|
|
),
|
|
}
|
|
follower_arms = {
|
|
"main": DynamixelMotorsBus(
|
|
port="/dev/tty.usbmodem575E0032081",
|
|
motors={
|
|
# name: (index, model)
|
|
"shoulder_pan": (1, "xl430-w250"),
|
|
"shoulder_lift": (2, "xl430-w250"),
|
|
"elbow_flex": (3, "xl330-m288"),
|
|
"wrist_flex": (4, "xl330-m288"),
|
|
"wrist_roll": (5, "xl330-m288"),
|
|
"gripper": (6, "xl330-m288"),
|
|
},
|
|
),
|
|
}
|
|
robot = ManipulatorRobot(
|
|
robot_type="koch",
|
|
calibration_dir=".cache/calibration/koch",
|
|
leader_arms=leader_arms,
|
|
follower_arms=follower_arms,
|
|
)
|
|
|
|
# Connect motors buses and cameras if any (Required)
|
|
robot.connect()
|
|
|
|
while True:
|
|
robot.teleop_step()
|
|
```
|
|
|
|
Example of highest frequency data collection without camera:
|
|
```python
|
|
# Assumes leader and follower arms have been instantiated already (see first example)
|
|
robot = ManipulatorRobot(
|
|
robot_type="koch",
|
|
calibration_dir=".cache/calibration/koch",
|
|
leader_arms=leader_arms,
|
|
follower_arms=follower_arms,
|
|
)
|
|
robot.connect()
|
|
while True:
|
|
observation, action = robot.teleop_step(record_data=True)
|
|
```
|
|
|
|
Example of highest frequency data collection with cameras:
|
|
```python
|
|
# Defines how to communicate with 2 cameras connected to the computer.
|
|
# Here, the webcam of the laptop and the phone (connected in USB to the laptop)
|
|
# can be reached respectively using the camera indices 0 and 1. These indices can be
|
|
# arbitrary. See the documentation of `OpenCVCamera` to find your own camera indices.
|
|
cameras = {
|
|
"laptop": OpenCVCamera(camera_index=0, fps=30, width=640, height=480),
|
|
"phone": OpenCVCamera(camera_index=1, fps=30, width=640, height=480),
|
|
}
|
|
|
|
# Assumes leader and follower arms have been instantiated already (see first example)
|
|
robot = ManipulatorRobot(
|
|
robot_type="koch",
|
|
calibration_dir=".cache/calibration/koch",
|
|
leader_arms=leader_arms,
|
|
follower_arms=follower_arms,
|
|
cameras=cameras,
|
|
)
|
|
robot.connect()
|
|
while True:
|
|
observation, action = robot.teleop_step(record_data=True)
|
|
```
|
|
|
|
Example of controlling the robot with a policy (without running multiple policies in parallel to ensure highest frequency):
|
|
```python
|
|
# Assumes leader and follower arms + cameras have been instantiated already (see previous example)
|
|
robot = ManipulatorRobot(
|
|
robot_type="koch",
|
|
calibration_dir=".cache/calibration/koch",
|
|
leader_arms=leader_arms,
|
|
follower_arms=follower_arms,
|
|
cameras=cameras,
|
|
)
|
|
robot.connect()
|
|
while True:
|
|
# Uses the follower arms and cameras to capture an observation
|
|
observation = robot.capture_observation()
|
|
|
|
# Assumes a policy has been instantiated
|
|
with torch.inference_mode():
|
|
action = policy.select_action(observation)
|
|
|
|
# Orders the robot to move
|
|
robot.send_action(action)
|
|
```
|
|
|
|
Example of disconnecting which is not mandatory since we disconnect when the object is deleted:
|
|
```python
|
|
robot.disconnect()
|
|
```
|
|
"""
|
|
|
|
def __init__(
|
|
self,
|
|
config: ManipulatorRobotConfig | None = None,
|
|
calibration_dir: Path = ".cache/calibration/koch",
|
|
**kwargs,
|
|
):
|
|
if config is None:
|
|
config = ManipulatorRobotConfig()
|
|
# Overwrite config arguments using kwargs
|
|
self.config = replace(config, **kwargs)
|
|
self.calibration_dir = Path(calibration_dir)
|
|
|
|
self.robot_type = self.config.robot_type
|
|
self.leader_arms = self.config.leader_arms
|
|
self.follower_arms = self.config.follower_arms
|
|
self.cameras = self.config.cameras
|
|
self.is_connected = False
|
|
self.logs = {}
|
|
|
|
def connect(self):
|
|
if self.is_connected:
|
|
raise RobotDeviceAlreadyConnectedError(
|
|
"ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
|
|
)
|
|
|
|
if not self.leader_arms and not self.follower_arms and not self.cameras:
|
|
raise ValueError(
|
|
"ManipulatorRobot doesn't have any device to connect. See example of usage in docstring of the class."
|
|
)
|
|
|
|
# Connect the arms
|
|
for name in self.follower_arms:
|
|
print(f"Connecting {name} follower arm.")
|
|
self.follower_arms[name].connect()
|
|
print(f"Connecting {name} leader arm.")
|
|
self.leader_arms[name].connect()
|
|
|
|
# We assume that at connection time, arms are in a rest position, and torque can
|
|
# be safely disabled to run calibration and/or set robot preset configurations.
|
|
for name in self.follower_arms:
|
|
self.follower_arms[name].write("Torque_Enable", TorqueMode.DISABLED.value)
|
|
for name in self.leader_arms:
|
|
self.leader_arms[name].write("Torque_Enable", TorqueMode.DISABLED.value)
|
|
|
|
self.activate_calibration()
|
|
|
|
# Set robot preset (e.g. torque in leader gripper for Koch v1.1)
|
|
if self.robot_type == "koch":
|
|
self.set_koch_robot_preset()
|
|
elif self.robot_type == "aloha":
|
|
self.set_aloha_robot_preset()
|
|
else:
|
|
warnings.warn(f"No preset found for robot type: {self.robot_type}", stacklevel=1)
|
|
|
|
# Enable torque on all motors of the follower arms
|
|
for name in self.follower_arms:
|
|
print(f"Activating torque on {name} follower arm.")
|
|
self.follower_arms[name].write("Torque_Enable", 1)
|
|
|
|
if self.config.gripper_open_degree is not None:
|
|
# Set the leader arm in torque mode with the gripper motor set to an angle. This makes it possible
|
|
# to squeeze the gripper and have it spring back to an open position on its own.
|
|
for name in self.leader_arms:
|
|
self.leader_arms[name].write("Torque_Enable", 1, "gripper")
|
|
self.leader_arms[name].write("Goal_Position", self.config.gripper_open_degree, "gripper")
|
|
|
|
# Connect the cameras
|
|
for name in self.cameras:
|
|
self.cameras[name].connect()
|
|
|
|
self.is_connected = True
|
|
|
|
def activate_calibration(self):
|
|
"""After calibration all motors function in human interpretable ranges.
|
|
Rotations are expressed in degrees in nominal range of [-180, 180],
|
|
and linear motions (like gripper of Aloha) in nominal range of [0, 100].
|
|
"""
|
|
|
|
def load_or_run_calibration_(name, arm, arm_type):
|
|
arm_id = get_arm_id(name, arm_type)
|
|
arm_calib_path = self.calibration_dir / f"{arm_id}.json"
|
|
|
|
if arm_calib_path.exists():
|
|
with open(arm_calib_path) as f:
|
|
calibration = json.load(f)
|
|
else:
|
|
print(f"Missing calibration file '{arm_calib_path}'")
|
|
calibration = run_arm_calibration(arm, self.robot_type, name, arm_type)
|
|
|
|
print(f"Calibration is done! Saving calibration file '{arm_calib_path}'")
|
|
arm_calib_path.parent.mkdir(parents=True, exist_ok=True)
|
|
with open(arm_calib_path, "w") as f:
|
|
json.dump(calibration, f)
|
|
|
|
return calibration
|
|
|
|
for name, arm in self.follower_arms.items():
|
|
calibration = load_or_run_calibration_(name, arm, "follower")
|
|
arm.set_calibration(calibration)
|
|
for name, arm in self.leader_arms.items():
|
|
calibration = load_or_run_calibration_(name, arm, "leader")
|
|
arm.set_calibration(calibration)
|
|
|
|
def set_koch_robot_preset(self):
|
|
def set_operating_mode_(arm):
|
|
if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
|
|
raise ValueError("To run set robot preset, the torque must be disabled on all motors.")
|
|
|
|
# Use 'extended position mode' for all motors except gripper, because in joint mode the servos can't
|
|
# rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while assembling the arm,
|
|
# you could end up with a servo with a position 0 or 4095 at a crucial point See [
|
|
# https://emanual.robotis.com/docs/en/dxl/x/x_series/#operating-mode11]
|
|
all_motors_except_gripper = [name for name in arm.motor_names if name != "gripper"]
|
|
if len(all_motors_except_gripper) > 0:
|
|
# 4 corresponds to Extended Position on Koch motors
|
|
arm.write("Operating_Mode", 4, all_motors_except_gripper)
|
|
|
|
# Use 'position control current based' for gripper to be limited by the limit of the current.
|
|
# For the follower gripper, it means it can grasp an object without forcing too much even tho,
|
|
# it's goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch).
|
|
# For the leader gripper, it means we can use it as a physical trigger, since we can force with our finger
|
|
# to make it move, and it will move back to its original target position when we release the force.
|
|
# 5 corresponds to Current Controlled Position on Koch gripper motors "xl330-m077, xl330-m288"
|
|
arm.write("Operating_Mode", 5, "gripper")
|
|
|
|
for name in self.follower_arms:
|
|
set_operating_mode_(self.follower_arms[name])
|
|
|
|
# Set better PID values to close the gap between recorded states and actions
|
|
# TODO(rcadene): Implement an automatic procedure to set optimial PID values for each motor
|
|
self.follower_arms[name].write("Position_P_Gain", 1500, "elbow_flex")
|
|
self.follower_arms[name].write("Position_I_Gain", 0, "elbow_flex")
|
|
self.follower_arms[name].write("Position_D_Gain", 600, "elbow_flex")
|
|
|
|
if self.config.gripper_open_degree is not None:
|
|
for name in self.leader_arms:
|
|
set_operating_mode_(self.leader_arms[name])
|
|
|
|
# Enable torque on the gripper of the leader arms, and move it to 45 degrees,
|
|
# so that we can use it as a trigger to close the gripper of the follower arms.
|
|
self.leader_arms[name].write("Torque_Enable", 1, "gripper")
|
|
self.leader_arms[name].write("Goal_Position", self.config.gripper_open_degree, "gripper")
|
|
|
|
def set_aloha_robot_preset(self):
|
|
def set_shadow_(arm):
|
|
# Set secondary/shadow ID for shoulder and elbow. These joints have two motors.
|
|
# As a result, if only one of them is required to move to a certain position,
|
|
# the other will follow. This is to avoid breaking the motors.
|
|
if "shoulder_shadow" in arm.motor_names:
|
|
shoulder_idx = arm.read("ID", "shoulder")
|
|
arm.write("Secondary_ID", shoulder_idx, "shoulder_shadow")
|
|
|
|
if "elbow_shadow" in arm.motor_names:
|
|
elbow_idx = arm.read("ID", "elbow")
|
|
arm.write("Secondary_ID", elbow_idx, "elbow_shadow")
|
|
|
|
for name in self.follower_arms:
|
|
set_shadow_(self.follower_arms[name])
|
|
|
|
for name in self.leader_arms:
|
|
set_shadow_(self.leader_arms[name])
|
|
|
|
for name in self.follower_arms:
|
|
# Set a velocity limit of 131 as advised by Trossen Robotics
|
|
self.follower_arms[name].write("Velocity_Limit", 131)
|
|
|
|
# Use 'extended position mode' for all motors except gripper, because in joint mode the servos can't
|
|
# rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while assembling the arm,
|
|
# you could end up with a servo with a position 0 or 4095 at a crucial point See [
|
|
# https://emanual.robotis.com/docs/en/dxl/x/x_series/#operating-mode11]
|
|
all_motors_except_gripper = [
|
|
name for name in self.follower_arms[name].motor_names if name != "gripper"
|
|
]
|
|
if len(all_motors_except_gripper) > 0:
|
|
# 4 corresponds to Extended Position on Aloha motors
|
|
self.follower_arms[name].write("Operating_Mode", 4, all_motors_except_gripper)
|
|
|
|
# Use 'position control current based' for follower gripper to be limited by the limit of the current.
|
|
# It can grasp an object without forcing too much even tho,
|
|
# it's goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch).
|
|
# 5 corresponds to Current Controlled Position on Aloha gripper follower "xm430-w350"
|
|
self.follower_arms[name].write("Operating_Mode", 5, "gripper")
|
|
|
|
# Note: We can't enable torque on the leader gripper since "xc430-w150" doesn't have
|
|
# a Current Controlled Position mode.
|
|
|
|
if self.config.gripper_open_degree is not None:
|
|
warnings.warn(
|
|
f"`gripper_open_degree` is set to {self.config.gripper_open_degree}, but None is expected for Aloha instead",
|
|
stacklevel=1,
|
|
)
|
|
|
|
def teleop_step(
|
|
self, record_data=False
|
|
) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]:
|
|
if not self.is_connected:
|
|
raise RobotDeviceNotConnectedError(
|
|
"ManipulatorRobot is not connected. You need to run `robot.connect()`."
|
|
)
|
|
|
|
# Prepare to assign the position of the leader to the follower
|
|
leader_pos = {}
|
|
for name in self.leader_arms:
|
|
before_lread_t = time.perf_counter()
|
|
leader_pos[name] = self.leader_arms[name].read("Present_Position")
|
|
leader_pos[name] = torch.from_numpy(leader_pos[name])
|
|
self.logs[f"read_leader_{name}_pos_dt_s"] = time.perf_counter() - before_lread_t
|
|
|
|
# Send goal position to the follower
|
|
follower_goal_pos = {}
|
|
for name in self.follower_arms:
|
|
before_fwrite_t = time.perf_counter()
|
|
goal_pos = leader_pos[name]
|
|
|
|
# Cap goal position when too far away from present position.
|
|
# Slower fps expected due to reading from the follower.
|
|
if self.config.max_relative_target is not None:
|
|
present_pos = self.follower_arms[name].read("Present_Position")
|
|
present_pos = torch.from_numpy(present_pos)
|
|
goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target)
|
|
|
|
# Used when record_data=True
|
|
follower_goal_pos[name] = goal_pos
|
|
|
|
goal_pos = goal_pos.numpy().astype(np.int32)
|
|
self.follower_arms[name].write("Goal_Position", goal_pos)
|
|
self.logs[f"write_follower_{name}_goal_pos_dt_s"] = time.perf_counter() - before_fwrite_t
|
|
|
|
# Early exit when recording data is not requested
|
|
if not record_data:
|
|
return
|
|
|
|
# TODO(rcadene): Add velocity and other info
|
|
# Read follower position
|
|
follower_pos = {}
|
|
for name in self.follower_arms:
|
|
before_fread_t = time.perf_counter()
|
|
follower_pos[name] = self.follower_arms[name].read("Present_Position")
|
|
follower_pos[name] = torch.from_numpy(follower_pos[name])
|
|
self.logs[f"read_follower_{name}_pos_dt_s"] = time.perf_counter() - before_fread_t
|
|
|
|
# Create state by concatenating follower current position
|
|
state = []
|
|
for name in self.follower_arms:
|
|
if name in follower_pos:
|
|
state.append(follower_pos[name])
|
|
state = torch.cat(state)
|
|
|
|
# Create action by concatenating follower goal position
|
|
action = []
|
|
for name in self.follower_arms:
|
|
if name in follower_goal_pos:
|
|
action.append(follower_goal_pos[name])
|
|
action = torch.cat(action)
|
|
|
|
# Capture images from cameras
|
|
images = {}
|
|
for name in self.cameras:
|
|
before_camread_t = time.perf_counter()
|
|
images[name] = self.cameras[name].async_read()
|
|
images[name] = torch.from_numpy(images[name])
|
|
self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"]
|
|
self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t
|
|
|
|
# Populate output dictionnaries
|
|
obs_dict, action_dict = {}, {}
|
|
obs_dict["observation.state"] = state
|
|
action_dict["action"] = action
|
|
for name in self.cameras:
|
|
obs_dict[f"observation.images.{name}"] = images[name]
|
|
|
|
return obs_dict, action_dict
|
|
|
|
def capture_observation(self):
|
|
"""The returned observations do not have a batch dimension."""
|
|
if not self.is_connected:
|
|
raise RobotDeviceNotConnectedError(
|
|
"ManipulatorRobot is not connected. You need to run `robot.connect()`."
|
|
)
|
|
|
|
# Read follower position
|
|
follower_pos = {}
|
|
for name in self.follower_arms:
|
|
before_fread_t = time.perf_counter()
|
|
follower_pos[name] = self.follower_arms[name].read("Present_Position")
|
|
follower_pos[name] = torch.from_numpy(follower_pos[name])
|
|
self.logs[f"read_follower_{name}_pos_dt_s"] = time.perf_counter() - before_fread_t
|
|
|
|
# Create state by concatenating follower current position
|
|
state = []
|
|
for name in self.follower_arms:
|
|
if name in follower_pos:
|
|
state.append(follower_pos[name])
|
|
state = torch.cat(state)
|
|
|
|
# Capture images from cameras
|
|
images = {}
|
|
for name in self.cameras:
|
|
before_camread_t = time.perf_counter()
|
|
images[name] = self.cameras[name].async_read()
|
|
images[name] = torch.from_numpy(images[name])
|
|
self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"]
|
|
self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t
|
|
|
|
# Populate output dictionnaries and format to pytorch
|
|
obs_dict = {}
|
|
obs_dict["observation.state"] = state
|
|
for name in self.cameras:
|
|
obs_dict[f"observation.images.{name}"] = images[name]
|
|
return obs_dict
|
|
|
|
def send_action(self, action: torch.Tensor) -> torch.Tensor:
|
|
"""Command the follower arms to move to a target joint configuration.
|
|
|
|
The relative action magnitude may be clipped depending on the configuration parameter
|
|
`max_relative_target`. In this case, the action sent differs from original action.
|
|
Thus, this function always returns the action actually sent.
|
|
|
|
Args:
|
|
action: tensor containing the concatenated goal positions for the follower arms.
|
|
"""
|
|
if not self.is_connected:
|
|
raise RobotDeviceNotConnectedError(
|
|
"ManipulatorRobot is not connected. You need to run `robot.connect()`."
|
|
)
|
|
|
|
from_idx = 0
|
|
to_idx = 0
|
|
action_sent = []
|
|
for name in self.follower_arms:
|
|
# Get goal position of each follower arm by splitting the action vector
|
|
to_idx += len(self.follower_arms[name].motor_names)
|
|
goal_pos = action[from_idx:to_idx]
|
|
from_idx = to_idx
|
|
|
|
# Cap goal position when too far away from present position.
|
|
# Slower fps expected due to reading from the follower.
|
|
if self.config.max_relative_target is not None:
|
|
present_pos = self.follower_arms[name].read("Present_Position")
|
|
present_pos = torch.from_numpy(present_pos)
|
|
goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target)
|
|
|
|
# Save tensor to concat and return
|
|
action_sent.append(goal_pos)
|
|
|
|
# Send goal position to each follower
|
|
goal_pos = goal_pos.numpy().astype(np.int32)
|
|
self.follower_arms[name].write("Goal_Position", goal_pos)
|
|
|
|
return torch.cat(action_sent)
|
|
|
|
def disconnect(self):
|
|
if not self.is_connected:
|
|
raise RobotDeviceNotConnectedError(
|
|
"ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
|
|
)
|
|
|
|
for name in self.follower_arms:
|
|
self.follower_arms[name].disconnect()
|
|
|
|
for name in self.leader_arms:
|
|
self.leader_arms[name].disconnect()
|
|
|
|
for name in self.cameras:
|
|
self.cameras[name].disconnect()
|
|
|
|
self.is_connected = False
|
|
|
|
def __del__(self):
|
|
if getattr(self, "is_connected", False):
|
|
self.disconnect()
|