fix(lekiwi): HW fixes v0.1
This commit is contained in:
parent
cb27f14f7b
commit
5130cba57a
|
@ -7,10 +7,12 @@ from lerobot.common.robots.config import RobotConfig
|
||||||
@dataclass
|
@dataclass
|
||||||
class DaemonLeKiwiRobotConfig(RobotConfig):
|
class DaemonLeKiwiRobotConfig(RobotConfig):
|
||||||
# Network Configuration
|
# Network Configuration
|
||||||
remote_ip: str = "192.168.0.193"
|
remote_ip: str = "172.18.133.90"
|
||||||
port_zmq_cmd: int = 5555
|
port_zmq_cmd: int = 5555
|
||||||
port_zmq_observations: int = 5556
|
port_zmq_observations: int = 5556
|
||||||
|
|
||||||
|
id = "daemonlekiwi"
|
||||||
|
|
||||||
teleop_keys: dict[str, str] = field(
|
teleop_keys: dict[str, str] = field(
|
||||||
default_factory=lambda: {
|
default_factory=lambda: {
|
||||||
# Movement
|
# Movement
|
||||||
|
|
|
@ -11,6 +11,8 @@ class LeKiwiRobotConfig(RobotConfig):
|
||||||
port_zmq_cmd: int = 5555
|
port_zmq_cmd: int = 5555
|
||||||
port_zmq_observations: int = 5556
|
port_zmq_observations: int = 5556
|
||||||
|
|
||||||
|
id = "lekiwi"
|
||||||
|
|
||||||
cameras: dict[str, CameraConfig] = field(
|
cameras: dict[str, CameraConfig] = field(
|
||||||
default_factory=lambda: {
|
default_factory=lambda: {
|
||||||
"front": OpenCVCameraConfig(
|
"front": OpenCVCameraConfig(
|
||||||
|
|
|
@ -3,10 +3,10 @@ import time
|
||||||
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
|
|
||||||
from ...teleoperators.keyboard import KeyboardTeleop, KeyboardTeleopConfig
|
from lerobot.common.robots.lekiwi.configuration_daemon_lekiwi import DaemonLeKiwiRobotConfig
|
||||||
from ...teleoperators.so100 import SO100Teleop, SO100TeleopConfig
|
from lerobot.common.robots.lekiwi.daemon_lekiwi import DaemonLeKiwiRobot, RobotMode
|
||||||
from .configuration_daemon_lekiwi import DaemonLeKiwiRobotConfig
|
from lerobot.common.teleoperators.keyboard import KeyboardTeleop, KeyboardTeleopConfig
|
||||||
from .daemon_lekiwi import DaemonLeKiwiRobot, RobotMode
|
from lerobot.common.teleoperators.so100 import SO100Teleop, SO100TeleopConfig
|
||||||
|
|
||||||
|
|
||||||
def main():
|
def main():
|
||||||
|
@ -45,7 +45,6 @@ def main():
|
||||||
# robot.set_mode(RobotMode.AUTO)
|
# robot.set_mode(RobotMode.AUTO)
|
||||||
# policy_action = policy.get_action() # This might be in body frame, key space or smt else
|
# policy_action = policy.get_action() # This might be in body frame, key space or smt else
|
||||||
# robot.send_action(policy_action)
|
# robot.send_action(policy_action)
|
||||||
|
|
||||||
duration = time.perf_counter() - start
|
duration = time.perf_counter() - start
|
||||||
|
|
||||||
logging.info("Disconnecting Teleop Devices and LeKiwiRobot Daemon")
|
logging.info("Disconnecting Teleop Devices and LeKiwiRobot Daemon")
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
import logging
|
import logging
|
||||||
|
|
||||||
from .configuration_lekiwi import LeKiwiRobotConfig
|
from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig
|
||||||
from .lekiwi_robot import LeKiwiRobot
|
from lerobot.common.robots.lekiwi.lekiwi_robot import LeKiwiRobot
|
||||||
|
|
||||||
|
|
||||||
def main():
|
def main():
|
||||||
|
|
|
@ -134,7 +134,7 @@ class LeKiwiRobot(Robot):
|
||||||
# We assume that at connection time, arm is in a rest position,
|
# We assume that at connection time, arm is in a rest position,
|
||||||
# and torque can be safely disabled to run calibration.
|
# and torque can be safely disabled to run calibration.
|
||||||
self.actuators_bus.write("Torque_Enable", TorqueMode.DISABLED.value, self.arm_actuators)
|
self.actuators_bus.write("Torque_Enable", TorqueMode.DISABLED.value, self.arm_actuators)
|
||||||
self.calibrate() # TODO(Steven): This should be only for the arm
|
# self.calibrate() # TODO(Steven): This should be only for the arm
|
||||||
|
|
||||||
# Mode=0 for Position Control
|
# Mode=0 for Position Control
|
||||||
self.actuators_bus.write("Mode", 0, self.arm_actuators)
|
self.actuators_bus.write("Mode", 0, self.arm_actuators)
|
||||||
|
@ -190,17 +190,15 @@ class LeKiwiRobot(Robot):
|
||||||
actuators_calib_path = self.calibration_dir / f"{self.config.id}.json"
|
actuators_calib_path = self.calibration_dir / f"{self.config.id}.json"
|
||||||
|
|
||||||
if actuators_calib_path.exists():
|
if actuators_calib_path.exists():
|
||||||
with open(actuators_calib_path,encoding="utf-8") as f:
|
with open(actuators_calib_path, encoding="utf-8") as f:
|
||||||
calibration = json.load(f)
|
calibration = json.load(f)
|
||||||
else:
|
else:
|
||||||
logging.info("Missing calibration file '%s'",actuators_calib_path)
|
logging.info("Missing calibration file '%s'", actuators_calib_path)
|
||||||
calibration = run_full_arm_calibration(
|
calibration = run_full_arm_calibration(self.actuators_bus, self.robot_type, self.name, "follower")
|
||||||
self.actuators_bus, self.robot_type, self.name, "follower"
|
|
||||||
)
|
|
||||||
|
|
||||||
logging.info("Calibration is done! Saving calibration file '%s'",actuators_calib_path)
|
logging.info("Calibration is done! Saving calibration file '%s'", actuators_calib_path)
|
||||||
actuators_calib_path.parent.mkdir(parents=True, exist_ok=True)
|
actuators_calib_path.parent.mkdir(parents=True, exist_ok=True)
|
||||||
with open(actuators_calib_path, "w",encoding="utf-8") as f:
|
with open(actuators_calib_path, "w", encoding="utf-8") as f:
|
||||||
json.dump(calibration, f)
|
json.dump(calibration, f)
|
||||||
|
|
||||||
self.actuators_bus.set_calibration(calibration)
|
self.actuators_bus.set_calibration(calibration)
|
||||||
|
@ -214,9 +212,12 @@ class LeKiwiRobot(Robot):
|
||||||
|
|
||||||
# Read actuators position for arm and vel for base
|
# Read actuators position for arm and vel for base
|
||||||
before_read_t = time.perf_counter()
|
before_read_t = time.perf_counter()
|
||||||
obs_dict[OBS_STATE] = self.actuators_bus.read(
|
obs_dict[OBS_STATE] = np.concatenate(
|
||||||
"Present_Position", self.arm_actuators
|
(
|
||||||
) + self.actuators_bus.read("Present_Speed", self.base_actuators)
|
self.actuators_bus.read("Present_Position", self.arm_actuators),
|
||||||
|
self.actuators_bus.read("Present_Speed", self.base_actuators),
|
||||||
|
)
|
||||||
|
)
|
||||||
self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
|
self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
|
||||||
|
|
||||||
# Capture images from cameras
|
# Capture images from cameras
|
||||||
|
@ -290,7 +291,7 @@ class LeKiwiRobot(Robot):
|
||||||
|
|
||||||
stop_event = threading.Event()
|
stop_event = threading.Event()
|
||||||
observation_thread = threading.Thread(
|
observation_thread = threading.Thread(
|
||||||
target=self.update_last_observation, args=(stop_event), daemon=True
|
target=self.update_last_observation, args=[stop_event], daemon=True
|
||||||
)
|
)
|
||||||
observation_thread.start()
|
observation_thread.start()
|
||||||
|
|
||||||
|
@ -302,14 +303,14 @@ class LeKiwiRobot(Robot):
|
||||||
loop_start_time = time.time()
|
loop_start_time = time.time()
|
||||||
|
|
||||||
try:
|
try:
|
||||||
msg = self.cmd_socket.recv_string(zmq.NOBLOCK)
|
msg = self.zmq_cmd_socket.recv_string(zmq.NOBLOCK)
|
||||||
data = json.loads(msg)
|
data = json.loads(msg)
|
||||||
self.send_action(data)
|
self.send_action(data)
|
||||||
last_cmd_time = time.time()
|
last_cmd_time = time.time()
|
||||||
# except zmq.Again:
|
except zmq.Again:
|
||||||
# logging.warning("ZMQ again")
|
logging.warning("ZMQ again")
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
logging.error("Message fetching failed: %s",e)
|
logging.error("Message fetching failed: %s", e)
|
||||||
|
|
||||||
# Watchdog: stop the robot if no command is received for over 0.5 seconds.
|
# Watchdog: stop the robot if no command is received for over 0.5 seconds.
|
||||||
now = time.time()
|
now = time.time()
|
||||||
|
@ -317,6 +318,7 @@ class LeKiwiRobot(Robot):
|
||||||
self.stop()
|
self.stop()
|
||||||
|
|
||||||
with self.observation_lock:
|
with self.observation_lock:
|
||||||
|
# TODO(Steven): This operation is blocking if no listener is available
|
||||||
self.zmq_observation_socket.send_string(json.dumps(self.last_observation))
|
self.zmq_observation_socket.send_string(json.dumps(self.last_observation))
|
||||||
|
|
||||||
# Ensure a short sleep to avoid overloading the CPU.
|
# Ensure a short sleep to avoid overloading the CPU.
|
||||||
|
@ -346,7 +348,7 @@ class LeKiwiRobot(Robot):
|
||||||
for cam in self.cameras.values():
|
for cam in self.cameras.values():
|
||||||
cam.disconnect()
|
cam.disconnect()
|
||||||
self.observation_socket.close()
|
self.observation_socket.close()
|
||||||
self.cmd_socket.close()
|
self.zmq_cmd_socket.close()
|
||||||
self.context.term()
|
self.context.term()
|
||||||
self.is_connected = False
|
self.is_connected = False
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
import abc
|
import abc
|
||||||
from pathlib import Path
|
from pathlib import Path
|
||||||
import enum
|
import enum
|
||||||
|
from pathlib import Path
|
||||||
from typing import Any
|
from typing import Any
|
||||||
|
|
||||||
import draccus
|
import draccus
|
||||||
|
@ -30,7 +31,9 @@ class Robot(abc.ABC):
|
||||||
self.robot_mode: RobotMode | None = None
|
self.robot_mode: RobotMode | None = None
|
||||||
self.id = config.id
|
self.id = config.id
|
||||||
self.calibration_dir = (
|
self.calibration_dir = (
|
||||||
config.calibration_dir if config.calibration_dir else HF_LEROBOT_CALIBRATION / ROBOTS / self.name
|
Path(config.calibration_dir)
|
||||||
|
if config.calibration_dir
|
||||||
|
else HF_LEROBOT_CALIBRATION / ROBOTS / self.name
|
||||||
)
|
)
|
||||||
self.calibration_dir.mkdir(parents=True, exist_ok=True)
|
self.calibration_dir.mkdir(parents=True, exist_ok=True)
|
||||||
self.calibration_fpath = self.calibration_dir / f"{self.id}.json"
|
self.calibration_fpath = self.calibration_dir / f"{self.id}.json"
|
||||||
|
|
Loading…
Reference in New Issue