Merge pull request #11 from wuphilipp/fixes

Bugfixes.
This commit is contained in:
Philipp Wu 2024-04-04 16:43:48 -07:00 committed by GitHub
commit 288888594a
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
7 changed files with 21 additions and 15 deletions

View file

@ -2,26 +2,26 @@ repos:
# remove unused python imports
- repo: https://github.com/myint/autoflake.git
rev: v2.1.1
rev: v2.3.1
hooks:
- id: autoflake
args: ["--in-place", "--remove-all-unused-imports", "--ignore-init-module-imports"]
# sort imports
- repo: https://github.com/timothycrosley/isort
rev: 5.12.0
rev: 5.13.2
hooks:
- id: isort
# code format according to black
- repo: https://github.com/ambv/black
rev: 23.3.0
rev: 24.3.0
hooks:
- id: black
# check for python styling with flake8
- repo: https://github.com/PyCQA/flake8
rev: 6.0.0
rev: 7.0.0
hooks:
- id: flake8
additional_dependencies: [
@ -33,6 +33,6 @@ repos:
# cleanup notebooks
- repo: https://github.com/kynan/nbstripout
rev: 0.6.1
rev: 0.7.1
hooks:
- id: nbstripout

View file

@ -31,7 +31,7 @@ docker build . -t gello:latest
We have provided an entry point into the docker container
```
python experiments/launch.py
python scripts/launch.py
```
# GELLO configuration setup (PLEASE READ)

View file

@ -1,4 +1,5 @@
"""Manipulator composer class."""
import abc
from pathlib import Path
from typing import Dict, List, Optional, Tuple, Union
@ -225,5 +226,5 @@ class ArmObservables(composer.Observables):
self.flange_position,
# self.flange_orientation,
# self.flange_velocity,
self.flange_angular_velocity,
# self.flange_angular_velocity,
] + self._collect_from_attachments("proprioception")

View file

@ -1,4 +1,5 @@
"""Simple floor arenas."""
from typing import Tuple
import numpy as np

View file

@ -1,4 +1,5 @@
"""A task where a walker must learn to stand."""
from typing import Optional
import numpy as np

View file

@ -20,7 +20,6 @@ ADDR_TORQUE_ENABLE = 64
ADDR_GOAL_POSITION = 116
LEN_GOAL_POSITION = 4
ADDR_PRESENT_POSITION = 132
ADDR_PRESENT_POSITION = 140
LEN_PRESENT_POSITION = 4
TORQUE_ENABLE = 1
TORQUE_DISABLE = 0
@ -237,8 +236,8 @@ class DynamixelDriver(DynamixelDriverProtocol):
# Return a copy of the joint_angles array to avoid race conditions
while self._joint_angles is None:
time.sleep(0.1)
with self._lock:
_j = self._joint_angles.copy()
# with self._lock:
_j = self._joint_angles.copy()
return _j / 2048.0 * np.pi
def close(self):
@ -257,10 +256,11 @@ def main():
except FileNotFoundError:
driver = DynamixelDriver(ids, port="/dev/cu.usbserial-FT7WBMUB")
# Test setting torque mode
driver.set_torque_mode(True)
driver.set_torque_mode(False)
# Print the joint angles
# Test reading the joint angles
try:
while True:
joint_angles = driver.get_joints()
@ -271,4 +271,4 @@ def main():
if __name__ == "__main__":
main()
main() # Test the driver

View file

@ -86,11 +86,14 @@ class DynamixelRobot(Robot):
if gripper_config is not None:
current_joints = current_joints[:-1]
start_joints = start_joints[:-1]
for c_joint, s_joint, joint_offset in zip(
current_joints, start_joints, self._joint_offsets
for idx, (c_joint, s_joint, joint_offset) in enumerate(
zip(current_joints, start_joints, self._joint_offsets)
):
new_joint_offsets.append(
np.pi * 2 * np.round((s_joint - c_joint) / (2 * np.pi))
np.pi
* 2
* np.round((-s_joint + c_joint) / (2 * np.pi))
* self._joint_signs[idx]
+ joint_offset
)
if gripper_config is not None: