Compare commits

...

16 Commits

Author SHA1 Message Date
nepyope
a72db65f62 working trained policy 2025-04-15 15:41:24 +02:00
nepyope
2488efa8bd add hopejr env 2025-04-13 14:30:29 +02:00
nepyope
5d9b4fcae9 hopejr_real 2025-04-13 14:28:05 +02:00
nepyope
c70054c0b9 added hopejr yaml 2025-04-13 14:10:27 +02:00
nepyope
62b1896304 rip this branch 2025-04-12 10:35:00 +02:00
Sebastian-Contrari
0306e18640 fix teleop 2025-04-11 16:28:06 +02:00
Sebastian-Contrari
54b685053e test scs 2025-04-10 17:14:40 +02:00
Sebastian-Contrari
5b7e25ed18 push new exoskeleton code 2025-04-10 16:21:34 +02:00
Sebastian-Contrari
f6e862d421 hopejr teleop code 2025-04-02 16:19:15 +02:00
Pepijn
91f549b2ce use float32 instead of int 2025-03-18 16:23:33 +01:00
nepyope
f945641de9 added SM8512BL 2025-01-14 14:19:38 +01:00
nepyope
5bd41a3dca added feetech failsafe comment 2025-01-09 18:14:01 +01:00
Remi Cadene
f996a13f70 Add test3 test4 2024-12-29 13:30:17 +01:00
Remi Cadene
743ebfa7c1 Cremaillaire HF 2024-12-24 11:33:55 +01:00
Remi Cadene
2c45660d77 WIP 2024-11-27 13:59:37 +01:00
Remi Cadene
9dd4414c6e fix autocalib moss 2024-10-26 10:43:52 +02:00
69 changed files with 9207 additions and 65 deletions

1
.gitignore vendored
View File

@@ -125,7 +125,6 @@ celerybeat.pid
# Environments
.env
.venv
env/
venv/
env.bak/
venv.bak/

BIN
examples.zip Normal file

Binary file not shown.

1
examples/hopejr/BOM Normal file
View File

@@ -0,0 +1 @@
Bearings - https://amzn.eu/d/8Xz7m4C - https://amzn.eu/d/1xOo8re - https://amzn.eu/d/9LXO205 (17x) - https://amzn.eu/d/eKGj9gf (2x) Bike Components - https://amzn.eu/d/cNiQi0O (1x) Accessories - https://amzn.eu/d/ipjCq1R (1x) - https://amzn.eu/d/0ZMzC3G (1x) Screws - https://amzn.eu/d/dzNhSkJ - https://amzn.eu/d/41AhVIU - https://amzn.eu/d/8G91txy - https://amzn.eu/d/9xu0pLa - https://amzn.eu/d/c5xaClV - https://amzn.eu/d/7kudpAo - https://amzn.eu/d/2BEgJFc - https://amzn.eu/d/4q9RNby - https://amzn.eu/d/4RE2lPV - https://amzn.eu/d/63YU0l1 Inserts - https://amzn.eu/d/7fjOtOC

624
examples/hopejr/README.md Normal file
View File

@@ -0,0 +1,624 @@
# Using the [SO-100](https://github.com/TheRobotStudio/SO-ARM100) with LeRobot
## Table of Contents
- [A. Source the parts](#a-source-the-parts)
- [B. Install LeRobot](#b-install-lerobot)
- [C. Configure the Motors](#c-configure-the-motors)
- [D. Step-by-Step Assembly Instructions](#d-step-by-step-assembly-instructions)
- [E. Calibrate](#e-calibrate)
- [F. Teleoperate](#f-teleoperate)
- [G. Record a dataset](#g-record-a-dataset)
- [H. Visualize a dataset](#h-visualize-a-dataset)
- [I. Replay an episode](#i-replay-an-episode)
- [J. Train a policy](#j-train-a-policy)
- [K. Evaluate your policy](#k-evaluate-your-policy)
- [L. More Information](#l-more-information)
## A. Source the parts
Follow this [README](https://github.com/TheRobotStudio/SO-ARM100). It contains the bill of materials, with a link to source the parts, as well as the instructions to 3D print the parts,
and advice if it's your first time printing or if you don't own a 3D printer.
Before assembling, you will first need to configure your motors. To this end, we provide a nice script, so let's first install LeRobot. After configuration, we will also guide you through assembly.
## B. Install LeRobot
> [!TIP]
> We use the Command Prompt (cmd) quite a lot. If you are not comfortable using the cmd or want to brush up using the command line you can have a look here: [Command line crash course](https://developer.mozilla.org/en-US/docs/Learn_web_development/Getting_started/Environment_setup/Command_line)
On your computer:
#### 1. [Install Miniconda](https://docs.anaconda.com/miniconda/install/#quick-command-line-install):
#### 2. Restart shell
Copy paste in your shell: `source ~/.bashrc` or for Mac: `source ~/.bash_profile` or `source ~/.zshrc` if you're using zshell
#### 3. Create and activate a fresh conda environment for lerobot
<details>
<summary><strong>Video install instructions</strong></summary>
<video src="https://github.com/user-attachments/assets/17172d3b-3b64-4b80-9cf1-b2b7c5cbd236"></video>
</details>
```bash
conda create -y -n lerobot python=3.10
```
Then activate your conda environment (do this each time you open a shell to use lerobot!):
```bash
conda activate lerobot
```
#### 4. Clone LeRobot:
```bash
git clone https://github.com/huggingface/lerobot.git ~/lerobot
```
#### 5. Install ffmpeg in your environment:
When using `miniconda`, install `ffmpeg` in your environment:
```bash
conda install ffmpeg -c conda-forge
```
#### 6. Install LeRobot with dependencies for the feetech motors:
```bash
cd ~/lerobot && pip install -e ".[feetech]"
```
Great :hugs:! You are now done installing LeRobot and we can begin assembling the SO100 arms :robot:.
Every time you now want to use LeRobot you can go to the `~/lerobot` folder where we installed LeRobot and run one of the commands.
## C. Configure the motors
> [!NOTE]
> Throughout this tutorial you will find videos on how to do the steps, the full video tutorial can be found here: [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I).
### 1. Find the USB ports associated to each arm
Designate one bus servo adapter and 6 motors for your leader arm, and similarly the other bus servo adapter and 6 motors for the follower arm. It's convenient to label them and write on each motor if it's for the follower `F` or for the leader `L` and it's ID from 1 to 6 (F1...F6 and L1...L6).
#### a. Run the script to find port
<details>
<summary><strong>Video finding port</strong></summary>
<video src="https://github.com/user-attachments/assets/4a21a14d-2046-4805-93c4-ee97a30ba33f"></video>
<video src="https://github.com/user-attachments/assets/1cc3aecf-c16d-4ff9-aec7-8c175afbbce2"></video>
</details>
To find the port for each bus servo adapter, run the utility script:
```bash
python lerobot/scripts/find_motors_bus_port.py
```
#### b. Example outputs
Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux):
```
Finding all available ports for the MotorBus.
['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
Remove the usb cable from your MotorsBus and press Enter when done.
[...Disconnect leader arm and press Enter...]
The port of this MotorsBus is /dev/tty.usbmodem575E0031751
Reconnect the usb cable.
```
Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux):
```
Finding all available ports for the MotorBus.
['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
Remove the usb cable from your MotorsBus and press Enter when done.
[...Disconnect follower arm and press Enter...]
The port of this MotorsBus is /dev/tty.usbmodem575E0032081
Reconnect the usb cable.
```
#### c. Troubleshooting
On Linux, you might need to give access to the USB ports by running:
```bash
sudo chmod 666 /dev/ttyACM0
sudo chmod 666 /dev/ttyACM1
```
#### d. Update config file
IMPORTANTLY: Now that you have your ports, update the **port** default values of [`SO100RobotConfig`](../lerobot/common/robot_devices/robots/configs.py). You will find something like:
```python
@RobotConfig.register_subclass("so100")
@dataclass
class So100RobotConfig(ManipulatorRobotConfig):
calibration_dir: str = ".cache/calibration/so100"
# `max_relative_target` limits 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.
max_relative_target: int | None = None
leader_arms: dict[str, MotorsBusConfig] = field(
default_factory=lambda: {
"main": FeetechMotorsBusConfig(
port="/dev/tty.usbmodem58760431091", <-- UPDATE HERE
motors={
# name: (index, model)
"shoulder_pan": [1, "sts3215"],
"shoulder_lift": [2, "sts3215"],
"elbow_flex": [3, "sts3215"],
"wrist_flex": [4, "sts3215"],
"wrist_roll": [5, "sts3215"],
"gripper": [6, "sts3215"],
},
),
}
)
follower_arms: dict[str, MotorsBusConfig] = field(
default_factory=lambda: {
"main": FeetechMotorsBusConfig(
port="/dev/tty.usbmodem585A0076891", <-- UPDATE HERE
motors={
# name: (index, model)
"shoulder_pan": [1, "sts3215"],
"shoulder_lift": [2, "sts3215"],
"elbow_flex": [3, "sts3215"],
"wrist_flex": [4, "sts3215"],
"wrist_roll": [5, "sts3215"],
"gripper": [6, "sts3215"],
},
),
}
)
```
### 2. Assembling the Base
Let's begin with assembling the follower arm base
#### a. Set IDs for all 12 motors
<details>
<summary><strong>Video configuring motor</strong></summary>
<video src="https://github.com/user-attachments/assets/ef9b3317-2e11-4858-b9d3-f0a02fb48ecf"></video>
<video src="https://github.com/user-attachments/assets/f36b5ed5-c803-4ebe-8947-b39278776a0d"></video>
</details>
Plug your first motor F1 and run this script to set its ID to 1. It will also set its present position to 2048, so expect your motor to rotate. Replace the text after --port to the corresponding follower control board port and run this command in cmd:
```bash
python lerobot/scripts/configure_motor.py \
--port /dev/tty.usbmodem58760432961 \
--brand feetech \
--model sts3215 \
--baudrate 1000000 \
--ID 1
```
> [!NOTE]
> These motors are currently limited. They can take values between 0 and 4096 only, which corresponds to a full turn. They can't turn more than that. 2048 is at the middle of this range, so we can take -2048 steps (180 degrees anticlockwise) and reach the maximum range, or take +2048 steps (180 degrees clockwise) and reach the maximum range. The configuration step also sets the homing offset to 0, so that if you misassembled the arm, you can always update the homing offset to account for a shift up to ± 2048 steps (± 180 degrees).
Then unplug your motor and plug the second motor and set its ID to 2.
```bash
python lerobot/scripts/configure_motor.py \
--port /dev/tty.usbmodem58760432961 \
--brand feetech \
--model sts3215 \
--baudrate 1000000 \
--ID 2
```
Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm.
#### b. Remove the gears of the 6 leader motors
<details>
<summary><strong>Video removing gears</strong></summary>
<video src="https://github.com/user-attachments/assets/0c95b88c-5b85-413d-ba19-aee2f864f2a7"></video>
</details>
Follow the video for removing gears. You need to remove the gear for the motors of the leader arm. As a result, you will only use the position encoding of the motor and reduce friction to more easily operate the leader arm.
## D. Step-by-Step Assembly Instructions
**Step 1: Clean Parts**
- Remove all support material from the 3D-printed parts.
---
### Additional Guidance
<details>
<summary><strong>Video assembling arms</strong></summary>
<video src="https://github.com/user-attachments/assets/488a39de-0189-4461-9de3-05b015f90cca"></video>
</details>
**Note:**
This video provides visual guidance for assembling the arms, but it doesn't specify when or how to do the wiring. Inserting the cables beforehand is much easier than doing it afterward. The first arm may take a bit more than 1 hour to assemble, but once you get used to it, you can assemble the second arm in under 1 hour.
---
### First Motor
**Step 2: Insert Wires**
- Insert two wires into the first motor.
<img src="../media/tutorial/img1.jpg" style="height:300px;">
**Step 3: Install in Base**
- Place the first motor into the base.
<img src="../media/tutorial/img2.jpg" style="height:300px;">
**Step 4: Secure Motor**
- Fasten the motor with 4 screws. Two from the bottom and two from top.
**Step 5: Attach Motor Holder**
- Slide over the first motor holder and fasten it using two screws (one on each side).
<img src="../media/tutorial/img4.jpg" style="height:300px;">
**Step 6: Attach Motor Horns**
- Install both motor horns, securing the top horn with a screw. Try not to move the motor position when attaching the motor horn, especially for the leader arms, where we removed the gears.
<img src="../media/tutorial/img5.jpg" style="height:300px;">
<details>
<summary><strong>Video adding motor horn</strong></summary>
<video src="https://github.com/user-attachments/assets/ef3391a4-ad05-4100-b2bd-1699bf86c969"></video>
</details>
**Step 7: Attach Shoulder Part**
- Route one wire to the back of the robot and the other to the left or in photo towards you (see photo).
- Attach the shoulder part.
<img src="../media/tutorial/img6.jpg" style="height:300px;">
**Step 8: Secure Shoulder**
- Tighten the shoulder part with 4 screws on top and 4 on the bottom
*(access bottom holes by turning the shoulder).*
---
### Second Motor Assembly
**Step 9: Install Motor 2**
- Slide the second motor in from the top and link the wire from motor 1 to motor 2.
<img src="../media/tutorial/img8.jpg" style="height:300px;">
**Step 10: Attach Shoulder Holder**
- Add the shoulder motor holder.
- Ensure the wire from motor 1 to motor 2 goes behind the holder while the other wire is routed upward (see photo).
- This part can be tight to assemble, you can use a workbench like the image or a similar setup to push the part around the motor.
<div style="display: flex;">
<img src="../media/tutorial/img9.jpg" style="height:250px;">
<img src="../media/tutorial/img10.jpg" style="height:250px;">
<img src="../media/tutorial/img12.jpg" style="height:250px;">
</div>
**Step 11: Secure Motor 2**
- Fasten the second motor with 4 screws.
**Step 12: Attach Motor Horn**
- Attach both motor horns to motor 2, again use the horn screw.
**Step 13: Attach Base**
- Install the base attachment using 2 screws.
<img src="../media/tutorial/img11.jpg" style="height:300px;">
**Step 14: Attach Upper Arm**
- Attach the upper arm with 4 screws on each side.
<img src="../media/tutorial/img13.jpg" style="height:300px;">
---
### Third Motor Assembly
**Step 15: Install Motor 3**
- Route the motor cable from motor 2 through the cable holder to motor 3, then secure motor 3 with 4 screws.
**Step 16: Attach Motor Horn**
- Attach both motor horns to motor 3 and secure one again with a horn screw.
<img src="../media/tutorial/img14.jpg" style="height:300px;">
**Step 17: Attach Forearm**
- Connect the forearm to motor 3 using 4 screws on each side.
<img src="../media/tutorial/img15.jpg" style="height:300px;">
---
### Fourth Motor Assembly
**Step 18: Install Motor 4**
- Slide in motor 4, attach the cable from motor 3, and secure the cable in its holder with a screw.
<div style="display: flex;">
<img src="../media/tutorial/img16.jpg" style="height:300px;">
<img src="../media/tutorial/img19.jpg" style="height:300px;">
</div>
**Step 19: Attach Motor Holder 4**
- Install the fourth motor holder (a tight fit). Ensure one wire is routed upward and the wire from motor 3 is routed downward (see photo).
<img src="../media/tutorial/img17.jpg" style="height:300px;">
**Step 20: Secure Motor 4 & Attach Horn**
- Fasten motor 4 with 4 screws and attach its motor horns, use for one a horn screw.
<img src="../media/tutorial/img18.jpg" style="height:300px;">
---
### Wrist Assembly
**Step 21: Install Motor 5**
- Insert motor 5 into the wrist holder and secure it with 2 front screws.
<img src="../media/tutorial/img20.jpg" style="height:300px;">
**Step 22: Attach Wrist**
- Connect the wire from motor 4 to motor 5. And already insert the other wire for the gripper.
- Secure the wrist to motor 4 using 4 screws on both sides.
<img src="../media/tutorial/img22.jpg" style="height:300px;">
**Step 23: Attach Wrist Horn**
- Install only one motor horn on the wrist motor and secure it with a horn screw.
<img src="../media/tutorial/img23.jpg" style="height:300px;">
---
### Follower Configuration
**Step 24: Attach Gripper**
- Attach the gripper to motor 5.
<img src="../media/tutorial/img24.jpg" style="height:300px;">
**Step 25: Install Gripper Motor**
- Insert the gripper motor, connect the motor wire from motor 5 to motor 6, and secure it with 3 screws on each side.
<img src="../media/tutorial/img25.jpg" style="height:300px;">
**Step 26: Attach Gripper Horn & Claw**
- Attach the motor horns and again use a horn screw.
- Install the gripper claw and secure it with 4 screws on both sides.
<img src="../media/tutorial/img26.jpg" style="height:300px;">
**Step 27: Mount Controller**
- Attach the motor controller on the back.
<div style="display: flex;">
<img src="../media/tutorial/img27.jpg" style="height:300px;">
<img src="../media/tutorial/img28.jpg" style="height:300px;">
</div>
*Assembly complete proceed to Leader arm assembly.*
---
### Leader Configuration
For the leader configuration, perform **Steps 123**. Make sure that you removed the motor gears from the motors.
**Step 24: Attach Leader Holder**
- Mount the leader holder onto the wrist and secure it with a screw.
<img src="../media/tutorial/img29.jpg" style="height:300px;">
**Step 25: Attach Handle**
- Attach the handle to motor 5 using 4 screws.
<img src="../media/tutorial/img30.jpg" style="height:300px;">
**Step 26: Install Gripper Motor**
- Insert the gripper motor, secure it with 3 screws on each side, attach a motor horn using a horn screw, and connect the motor wire.
<img src="../media/tutorial/img31.jpg" style="height:300px;">
**Step 27: Attach Trigger**
- Attach the follower trigger with 4 screws.
<img src="../media/tutorial/img32.jpg" style="height:300px;">
**Step 28: Mount Controller**
- Attach the motor controller on the back.
<div style="display: flex;">
<img src="../media/tutorial/img27.jpg" style="height:300px;">
<img src="../media/tutorial/img28.jpg" style="height:300px;">
</div>
*Assembly complete proceed to calibration.*
## E. Calibrate
Next, you'll need to calibrate your SO-100 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one SO-100 robot to work on another.
#### a. Manual calibration of follower arm
> [!IMPORTANT]
> Contrarily to step 6 of the [assembly video](https://youtu.be/FioA2oeFZ5I?t=724) which illustrates the auto calibration, we will actually do manual calibration of follower for now.
You will need to move the follower arm to these positions sequentially:
| 1. Zero position | 2. Rotated position | 3. Rest position |
| ------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <img src="../media/so100/follower_zero.webp?raw=true" alt="SO-100 follower arm zero position" title="SO-100 follower arm zero position" style="width:100%;"> | <img src="../media/so100/follower_rotated.webp?raw=true" alt="SO-100 follower arm rotated position" title="SO-100 follower arm rotated position" style="width:100%;"> | <img src="../media/so100/follower_rest.webp?raw=true" alt="SO-100 follower arm rest position" title="SO-100 follower arm rest position" style="width:100%;"> |
Make sure both arms are connected and run this script to launch manual calibration:
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--robot.cameras='{}' \
--control.type=calibrate \
--control.arms='["main_follower"]'
```
#### b. Manual calibration of leader arm
Follow step 6 of the [assembly video](https://youtu.be/FioA2oeFZ5I?t=724) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially:
| 1. Zero position | 2. Rotated position | 3. Rest position |
| ------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------ |
| <img src="../media/so100/leader_zero.webp?raw=true" alt="SO-100 leader arm zero position" title="SO-100 leader arm zero position" style="width:100%;"> | <img src="../media/so100/leader_rotated.webp?raw=true" alt="SO-100 leader arm rotated position" title="SO-100 leader arm rotated position" style="width:100%;"> | <img src="../media/so100/leader_rest.webp?raw=true" alt="SO-100 leader arm rest position" title="SO-100 leader arm rest position" style="width:100%;"> |
Run this script to launch manual calibration:
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--robot.cameras='{}' \
--control.type=calibrate \
--control.arms='["main_leader"]'
```
## F. Teleoperate
**Simple teleop**
Then you are ready to teleoperate your robot! Run this simple script (it won't connect and display the cameras):
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--robot.cameras='{}' \
--control.type=teleoperate
```
#### a. Teleop with displaying cameras
Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset.
> **NOTE:** To visualize the data, enable `--control.display_data=true`. This streams the data using `rerun`.
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--control.type=teleoperate
```
## G. Record a dataset
Once you're familiar with teleoperation, you can record your first dataset with SO-100.
If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens):
```bash
huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential
```
Store your Hugging Face repository name in a variable to run these commands:
```bash
HF_USER=$(huggingface-cli whoami | head -n 1)
echo $HF_USER
```
Record 2 episodes and upload your dataset to the hub:
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--control.type=record \
--control.fps=30 \
--control.single_task="Grasp a lego block and put it in the bin." \
--control.repo_id=${HF_USER}/so100_test \
--control.tags='["so100","tutorial"]' \
--control.warmup_time_s=5 \
--control.episode_time_s=30 \
--control.reset_time_s=30 \
--control.num_episodes=2 \
--control.push_to_hub=true
```
Note: You can resume recording by adding `--control.resume=true`.
## H. Visualize a dataset
If you uploaded your dataset to the hub with `--control.push_to_hub=true`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by:
```bash
echo ${HF_USER}/so100_test
```
If you didn't upload with `--control.push_to_hub=false`, you can also visualize it locally with (a window can be opened in the browser `http://127.0.0.1:9090` with the visualization tool):
```bash
python lerobot/scripts/visualize_dataset_html.py \
--repo-id ${HF_USER}/so100_test \
--local-files-only 1
```
## I. Replay an episode
Now try to replay the first episode on your robot:
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--control.type=replay \
--control.fps=30 \
--control.repo_id=${HF_USER}/so100_test \
--control.episode=0
```
## J. Train a policy
To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command:
```bash
python lerobot/scripts/train.py \
--dataset.repo_id=${HF_USER}/so100_test \
--policy.type=act \
--output_dir=outputs/train/act_so100_test \
--job_name=act_so100_test \
--policy.device=cuda \
--wandb.enable=true
```
Let's explain it:
1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/so100_test`.
2. We provided the policy with `policy.type=act`. This loads configurations from [`configuration_act.py`](../lerobot/common/policies/act/configuration_act.py). Importantly, this policy will automatically adapt to the number of motor sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset.
4. We provided `policy.device=cuda` since we are training on a Nvidia GPU, but you could use `policy.device=mps` to train on Apple silicon.
5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`.
Training should take several hours. You will find checkpoints in `outputs/train/act_so100_test/checkpoints`.
To resume training from a checkpoint, below is an example command to resume from `last` checkpoint of the `act_so100_test` policy:
```bash
python lerobot/scripts/train.py \
--config_path=outputs/train/act_so100_test/checkpoints/last/pretrained_model/train_config.json \
--resume=true
```
## K. Evaluate your policy
You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes:
```bash
python lerobot/scripts/control_robot.py \
--robot.type=so100 \
--control.type=record \
--control.fps=30 \
--control.single_task="Grasp a lego block and put it in the bin." \
--control.repo_id=${HF_USER}/eval_act_so100_test \
--control.tags='["tutorial"]' \
--control.warmup_time_s=5 \
--control.episode_time_s=30 \
--control.reset_time_s=30 \
--control.num_episodes=10 \
--control.push_to_hub=true \
--control.policy.path=outputs/train/act_so100_test/checkpoints/last/pretrained_model
```
As you can see, it's almost the same command as previously used to record your training dataset. Two things changed:
1. There is an additional `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_act_so100_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `${HF_USER}/act_so100_test`).
2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_so100_test`).
## L. More Information
Follow this [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) for a more in-depth tutorial on controlling real robots with LeRobot.
> [!TIP]
> If you have any questions or need help, please reach out on [Discord](https://discord.com/invite/s3KuuzsPFb) in the channel [`#so100-arm`](https://discord.com/channels/1216765309076115607/1237741463832363039).

45
examples/hopejr/agugu.py Normal file
View File

@@ -0,0 +1,45 @@
import time
import numpy as np
from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus, CalibrationMode
@staticmethod
def degps_to_raw(degps: float) -> int:
steps_per_deg = 4096.0 / 360.0
speed_in_steps = abs(degps) * steps_per_deg
speed_int = int(round(speed_in_steps))
if speed_int > 0x7FFF:
speed_int = 0x7FFF
if degps < 0:
return speed_int | 0x8000
else:
return speed_int & 0x7FFF
@staticmethod
def raw_to_degps(raw_speed: int) -> float:
steps_per_deg = 4096.0 / 360.0
magnitude = raw_speed & 0x7FFF
degps = magnitude / steps_per_deg
if raw_speed & 0x8000:
degps = -degps
return degps
def main():
# Instantiate the bus for a single motor on port /dev/ttyACM0.
arm_bus = FeetechMotorsBus(
port="/dev/ttyACM0",
motors={"wrist_pitch": [1, "scs0009"]},
protocol_version=1,
group_sync_read=False, # using individual read calls
)
arm_bus.connect()
# Read the current raw motor position.
# Note that "Present_Position" is in the raw units.
current_raw = arm_bus.read("Present_Position", ["wrist_pitch"])[0]
print("Current raw position:", current_raw)
arm_bus.write("Goal_Position", 1000)
arm_bus.disconnect()
exit()
if __name__ == "__main__":
main()

BIN
examples/hopejr/asd.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 148 KiB

View File

@@ -0,0 +1,46 @@
import serial
import matplotlib.pyplot as plt
import matplotlib.animation as animation
from collections import deque
# Adjust this to match your actual serial port and baud rate
SERIAL_PORT = '/dev/ttyACM0' # or COM3 on Windows
BAUD_RATE = 115200
# Set up serial connection
ser = serial.Serial(SERIAL_PORT, BAUD_RATE)
# Buffers for real-time plot
buffer_len = 200
val1_buffer = deque([0]*buffer_len, maxlen=buffer_len)
val2_buffer = deque([0]*buffer_len, maxlen=buffer_len)
# Setup the plot
fig, ax = plt.subplots()
line1, = ax.plot([], [], label='Sensor 0')
line2, = ax.plot([], [], label='Sensor 1')
ax.set_ylim(0, 4096)
ax.set_xlim(0, buffer_len)
ax.legend()
def update(frame):
while ser.in_waiting:
line = ser.readline().decode('utf-8').strip()
parts = line.split()
if len(parts) >= 2:
try:
val1 = int(parts[0])
val2 = int(parts[1])
val1_buffer.append(val1)
val2_buffer.append(val2)
except ValueError:
pass # skip malformed lines
line1.set_ydata(val1_buffer)
line1.set_xdata(range(len(val1_buffer)))
line2.set_ydata(val2_buffer)
line2.set_xdata(range(len(val2_buffer)))
return line1, line2
ani = animation.FuncAnimation(fig, update, interval=50)
plt.show()

View File

@@ -0,0 +1,64 @@
import serial
import matplotlib.pyplot as plt
import matplotlib.animation as animation
from collections import deque
# Config
SERIAL_PORT = '/dev/ttyACM1' # Change as needed
BAUD_RATE = 115200
BUFFER_LEN = 200
# Sensor names in order
sensor_names = [
"wrist_roll",
"wrist_pitch",
"wrist_yaw",
"elbow_flex",
"shoulder_roll",
"shoulder_yaw",
"shoulder_pitch"
]
# Initialize buffers
sensor_data = {
name: deque([0]*BUFFER_LEN, maxlen=BUFFER_LEN)
for name in sensor_names
}
# Setup plot
fig, axes = plt.subplots(len(sensor_names), 1, figsize=(8, 12), sharex=True)
fig.tight_layout(pad=3.0)
lines = {}
for i, name in enumerate(sensor_names):
axes[i].set_title(name)
axes[i].set_xlim(0, BUFFER_LEN)
axes[i].set_ylim(0, 4096)
line, = axes[i].plot([], [], label=name)
axes[i].legend()
lines[name] = line
# Connect to serial
ser = serial.Serial(SERIAL_PORT, BAUD_RATE)
# Update function
def update(frame):
while ser.in_waiting:
line = ser.readline().decode().strip()
parts = line.split()
if len(parts) != 7:
continue
try:
values = list(map(int, parts))
except ValueError:
continue
for i, name in enumerate(sensor_names):
sensor_data[name].append(values[i])
for name in sensor_names:
x = range(len(sensor_data[name]))
lines[name].set_data(x, sensor_data[name])
return lines.values()
# Animate
ani = animation.FuncAnimation(fig, update, interval=50, blit=False)
plt.show()

View File

@@ -0,0 +1,161 @@
import serial
import matplotlib.pyplot as plt
import matplotlib.animation as animation
from collections import deque
# Adjust this to match your actual serial port and baud rate
SERIAL_PORT = '/dev/ttyACM0' # or COM3 on Windows
BAUD_RATE = 115200
# Set up serial connection
ser = serial.Serial(SERIAL_PORT, BAUD_RATE)
# How many data points to keep in the scrolling buffer
buffer_len = 200
# -------------------------------------------------------------------
# 1) Sensor buffers for existing sensors + new wrist_pitch, wrist_yaw
# -------------------------------------------------------------------
sensor_buffers = {
'wrist_roll': {
'val1': deque([0]*buffer_len, maxlen=buffer_len),
'val2': deque([0]*buffer_len, maxlen=buffer_len)
},
'elbow_pitch': {
'val1': deque([0]*buffer_len, maxlen=buffer_len),
'val2': deque([0]*buffer_len, maxlen=buffer_len)
},
'shoulder_pitch': {
'val1': deque([0]*buffer_len, maxlen=buffer_len),
'val2': deque([0]*buffer_len, maxlen=buffer_len)
},
'shoulder_yaw': {
'val1': deque([0]*buffer_len, maxlen=buffer_len),
'val2': deque([0]*buffer_len, maxlen=buffer_len)
},
'shoulder_roll': {
'val1': deque([0]*buffer_len, maxlen=buffer_len),
'val2': deque([0]*buffer_len, maxlen=buffer_len)
},
# --- New single-valued sensors ---
'wrist_pitch': {
'val1': deque([0]*buffer_len, maxlen=buffer_len) # Only one line
},
'wrist_yaw': {
'val1': deque([0]*buffer_len, maxlen=buffer_len) # Only one line
},
}
# -------------------------------------------------------------------
# 2) Figure with 7 subplots (was 5). We keep the original 5 + 2 new.
# -------------------------------------------------------------------
fig, axes = plt.subplots(7, 1, figsize=(8, 14), sharex=True)
fig.tight_layout(pad=3.0)
# We'll store line references in a dict so we can update them in update().
lines = {}
# -------------------------------------------------------------------
# 3) Define each subplot, including new ones at the end.
# -------------------------------------------------------------------
subplot_info = [
('wrist_roll', 'Wrist Roll (2,3)', axes[0]),
('elbow_pitch', 'Elbow Pitch (0,1)', axes[1]),
('shoulder_pitch', 'Shoulder Pitch (10,11)', axes[2]),
('shoulder_yaw', 'Shoulder Yaw (12,13)', axes[3]),
('shoulder_roll', 'Shoulder Roll (14,15)', axes[4]),
('wrist_pitch', 'Wrist Pitch (0)', axes[5]), # new
('wrist_yaw', 'Wrist Yaw (1)', axes[6]), # new
]
# Set up each subplot
for (sensor_name, label, ax) in subplot_info:
ax.set_title(label)
ax.set_xlim(0, buffer_len)
ax.set_ylim(0, 4096) # adjust if needed
# For existing sensors, plot 2 lines (val1, val2)
# For the new single-line sensors, plot just 1 line
if sensor_name in ['wrist_pitch', 'wrist_yaw']:
# Single-valued
line, = ax.plot([], [], label=f"{sensor_name}")
lines[sensor_name] = line
else:
# Pair of values
line1, = ax.plot([], [], label=f"{sensor_name} - val1")
line2, = ax.plot([], [], label=f"{sensor_name} - val2")
lines[sensor_name] = [line1, line2]
ax.legend()
def update(frame):
# Read all available lines from the serial buffer
while ser.in_waiting:
raw_line = ser.readline().decode('utf-8').strip()
parts = raw_line.split()
# We expect at least 16 values if all sensors are present
if len(parts) < 7:
continue
try:
values = list(map(int, parts))
except ValueError:
# If there's a parsing error, skip this line
continue
# Original code: extract the relevant values and append to the correct buffer
sensor_buffers['elbow_pitch']['val1'].append(values[13])
sensor_buffers['elbow_pitch']['val2'].append(values[13])
sensor_buffers['wrist_roll']['val1'].append(values[3])
sensor_buffers['wrist_roll']['val2'].append(values[3])
sensor_buffers['shoulder_pitch']['val1'].append(values[14])
sensor_buffers['shoulder_pitch']['val2'].append(values[14])
sensor_buffers['shoulder_yaw']['val1'].append(values[8])
sensor_buffers['shoulder_yaw']['val2'].append(values[8])
sensor_buffers['shoulder_roll']['val1'].append(values[10])
sensor_buffers['shoulder_roll']['val2'].append(values[10])
# -------------------------------------------------------------------
# 4) New code: also read wrist_pitch (index 0) and wrist_yaw (index 1)
# -------------------------------------------------------------------
sensor_buffers['wrist_yaw']['val1'].append(values[0])
sensor_buffers['wrist_pitch']['val1'].append(values[1])
# Update each line's data in each subplot
all_lines = []
for (sensor_name, _, ax) in subplot_info:
# x-values are just the index range of the buffer for val1
x_data = range(len(sensor_buffers[sensor_name]['val1']))
# If this sensor has two lines
if isinstance(lines[sensor_name], list):
# First line
lines[sensor_name][0].set_data(
x_data,
sensor_buffers[sensor_name]['val1']
)
# Second line
lines[sensor_name][1].set_data(
x_data,
sensor_buffers[sensor_name]['val2']
)
all_lines.extend(lines[sensor_name])
else:
# Single line only (wrist_pitch, wrist_yaw)
lines[sensor_name].set_data(
x_data,
sensor_buffers[sensor_name]['val1']
)
all_lines.append(lines[sensor_name])
return all_lines
# Create the animation
ani = animation.FuncAnimation(fig, update, interval=50, blit=False)
plt.show()

186
examples/hopejr/follower.py Normal file
View File

@@ -0,0 +1,186 @@
from lerobot.common.robot_devices.motors.feetech import (
CalibrationMode,
FeetechMotorsBus,
)
import yaml
class HopeJuniorRobot:
def __init__(self):
self.arm_port = "/dev/tty.usbserial-140"
self.hand_port = "/dev/tty.usbmodem58760436961"
self.arm_bus = FeetechMotorsBus(
port = self.arm_port,
motors={
# "motor1": (1, "sts3250"),
# "motor2": (2, "sts3250"),
# "motor3": (3, "sts3250"),
#"shoulder_pitch": [1, "sts3215"],
"shoulder_pitch": [1, "sm8512bl"],
"shoulder_yaw": [2, "sts3250"], # TODO: sts3250
"shoulder_roll": [3, "sts3250"], # TODO: sts3250
"elbow_flex": [4, "sts3250"],
"wrist_roll": [5, "sts3215"],
"wrist_yaw": [6, "sts3215"],
"wrist_pitch": [7, "sts3215"],
},
protocol_version=0,
)
self.hand_bus = FeetechMotorsBus(
port=self.hand_port,
motors = {
# Thumb
"thumb_basel_rotation": [1, "scs0009"],
"thumb_mcp": [3, "scs0009"],
"thumb_pip": [4, "scs0009"],
"thumb_dip": [13, "scs0009"],
# Index
"index_thumb_side": [5, "scs0009"],
"index_pinky_side": [6, "scs0009"],
"index_flexor": [16, "scs0009"],
# Middle
"middle_thumb_side": [8, "scs0009"],
"middle_pinky_side": [9, "scs0009"],
"middle_flexor": [2, "scs0009"],
# Ring
"ring_thumb_side": [11, "scs0009"],
"ring_pinky_side": [12, "scs0009"],
"ring_flexor": [7, "scs0009"],
# Pinky
"pinky_thumb_side": [14, "scs0009"],
"pinky_pinky_side": [15, "scs0009"],
"pinky_flexor": [10, "scs0009"],
},
protocol_version=1,#1
group_sync_read=False,
)
self.arm_calib_dict = self.get_arm_calibration()
self.hand_calib_dict = self.get_hand_calibration()
def apply_arm_config(self, config_file):
with open(config_file, "r") as file:
config = yaml.safe_load(file)
for param, value in config.get("robot", {}).get("arm_bus", {}).items():
self.arm_bus.write(param, value)
def apply_hand_config(config_file, robot):
with open(config_file, "r") as file:
config = yaml.safe_load(file)
for param, value in config.get("robot", {}).get("hand_bus", {}).items():
robot.arm_bus.write(param, value)
def get_hand_calibration(self):
homing_offset = [0] * len(self.hand_bus.motor_names)
drive_mode = [0] * len(self.hand_bus.motor_names)
start_pos = [
750, # thumb_basel_rotation
100, # thumb_mcp
700, # thumb_pip
100, # thumb_dip
800, # index_thumb_side
950, # index_pinky_side
0, # index_flexor
250, # middle_thumb_side
850, # middle_pinky_side
0, # middle_flexor
850, # ring_thumb_side
900, # ring_pinky_side
0, # ring_flexor
00, # pinky_thumb_side
950, # pinky_pinky_side
0, # pinky_flexor
]
end_pos = [
start_pos[0] - 550, # thumb_basel_rotation
start_pos[1] + 400, # thumb_mcp
start_pos[2] + 300, # thumb_pip
start_pos[3] + 200, # thumb_dip
start_pos[4] - 700, # index_thumb_side
start_pos[5] - 300, # index_pinky_side
start_pos[6] + 600, # index_flexor
start_pos[7] + 700, # middle_thumb_side
start_pos[8] - 400, # middle_pinky_side
start_pos[9] + 600, # middle_flexor
start_pos[10] - 600, # ring_thumb_side
start_pos[11] - 400, # ring_pinky_side
start_pos[12] + 600, # ring_flexor
start_pos[13] + 400, # pinky_thumb_side
start_pos[14] - 450, # pinky_pinky_side
start_pos[15] + 600, # pinky_flexor
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.hand_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.hand_bus.motor_names,
}
return calib_dict
def get_arm_calibration(self):
homing_offset = [0] * len(self.arm_bus.motor_names)
drive_mode = [0] * len(self.arm_bus.motor_names)
start_pos = [
1800, # shoulder_up
2800, # shoulder_forward
1800, # shoulder_roll
1200, # bend_elbow
700, # wrist_roll
1850, # wrist_yaw
1700, # wrist_pitch
]
end_pos = [
2800, # shoulder_up
3150, # shoulder_forward
400, #shoulder_roll
2300, # bend_elbow
2300, # wrist_roll
2150, # wrist_yaw
2300, # wrist_pitch
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.arm_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.arm_bus.motor_names,
}
return calib_dict
def connect_arm(self):
self.arm_bus.connect()
def connect_hand(self):
self.hand_bus.connect()

730
examples/hopejr/leader.py Normal file
View File

@@ -0,0 +1,730 @@
from lerobot.common.robot_devices.motors.feetech import (
CalibrationMode,
FeetechMotorsBus,
)
import serial
import threading
import time
from typing import Callable
import pickle
import cv2
import numpy as np
from collections import deque
import json
import os
LOWER_BOUND_LINEAR = -100
UPPER_BOUND_LINEAR = 200
class HomonculusArm:
def __init__(self, serial_port: str = "/dev/ttyACM1", baud_rate: int = 115200):
self.serial_port = serial_port
self.baud_rate = 115200
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
# Number of past values to keep in memory
self.buffer_size = 10
# Initialize a buffer (deque) for each joint
self.joint_buffer = {
"wrist_roll": deque(maxlen=self.buffer_size),
"wrist_pitch": deque(maxlen=self.buffer_size),
"wrist_yaw": deque(maxlen=self.buffer_size),
"elbow_flex": deque(maxlen=self.buffer_size),
"shoulder_roll": deque(maxlen=self.buffer_size),
"shoulder_yaw": deque(maxlen=self.buffer_size),
"shoulder_pitch": deque(maxlen=self.buffer_size),
}
# Start the reading thread
self.thread = threading.Thread(target=self.async_read, daemon=True)
self.thread.start()
# Last read dictionary
self.last_d = {
"wrist_roll": 100,
"wrist_pitch": 100,
"wrist_yaw": 100,
"elbow_flex": 100,
"shoulder_roll": 100,
"shoulder_yaw": 100,
"shoulder_pitch": 100,
}
self.calibration = None
# For adaptive EMA, we store a "previous smoothed" state per joint
self.adaptive_ema_state = {
"wrist_roll": None,
"wrist_pitch": None,
"wrist_yaw": None,
"elbow_flex": None,
"shoulder_roll": None,
"shoulder_yaw": None,
"shoulder_pitch": None,
}
self.kalman_state = {
joint: {"x": None, "P": None} for joint in self.joint_buffer.keys()
}
@property
def joint_names(self):
return list(self.last_d.keys())
def read(self, motor_names: list[str] | None = None):
"""
Return the most recent (single) values from self.last_d,
optionally applying calibration.
"""
if motor_names is None:
motor_names = self.joint_names
# Get raw (last) values
values = np.array([self.last_d[k] for k in motor_names])
#print(motor_names)
print(values)
# Apply calibration if available
if self.calibration is not None:
values = self.apply_calibration(values, motor_names)
print(values)
return values
def read_running_average(self, motor_names: list[str] | None = None, linearize=False):
"""
Return the AVERAGE of the most recent self.buffer_size (or fewer, if not enough data) readings
for each joint, optionally applying calibration.
"""
if motor_names is None:
motor_names = self.joint_names
# Gather averaged readings from buffers
smoothed_vals = []
for name in motor_names:
buf = self.joint_buffer[name]
if len(buf) == 0:
# If no data has been read yet, fall back to last_d
smoothed_vals.append(self.last_d[name])
else:
# Otherwise, average over the existing buffer
smoothed_vals.append(np.mean(buf))
smoothed_vals = np.array(smoothed_vals, dtype=np.float32)
# Apply calibration if available
if self.calibration is not None:
if False:
for i, joint_name in enumerate(motor_names):
# Re-use the same raw_min / raw_max from the calibration
calib_idx = self.calibration["motor_names"].index(joint_name)
min_reading = self.calibration["start_pos"][calib_idx]
max_reading = self.calibration["end_pos"][calib_idx]
B_value = smoothed_vals[i]
print(joint_name)
if joint_name == "elbow_flex":
print('elbow')
try:
smoothed_vals[i] = int(min_reading+(max_reading - min_reading)*np.arcsin((B_value-min_reading)/(max_reading-min_reading))/(np.pi / 2))
except:
print('not working')
print(smoothed_vals)
print('not working')
smoothed_vals = self.apply_calibration(smoothed_vals, motor_names)
return smoothed_vals
def read_kalman_filter(
self,
Q: float = 1.0,
R: float = 100.0,
motor_names: list[str] | None = None
) -> np.ndarray:
"""
Return a Kalman-filtered reading for each requested joint.
We store a separate Kalman filter (x, P) per joint. For each new measurement Z:
1) Predict:
x_pred = x (assuming no motion model)
P_pred = P + Q
2) Update:
K = P_pred / (P_pred + R)
x = x_pred + K * (Z - x_pred)
P = (1 - K) * P_pred
:param Q: Process noise. Larger Q means the estimate can change more freely.
:param R: Measurement noise. Larger R means we trust our sensor less.
:param motor_names: If not specified, all joints are filtered.
:return: Kalman-filtered positions as a numpy array.
"""
if motor_names is None:
motor_names = self.joint_names
current_vals = np.array([self.last_d[name] for name in motor_names], dtype=np.float32)
filtered_vals = np.zeros_like(current_vals)
for i, name in enumerate(motor_names):
# Retrieve the filter state for this joint
x = self.kalman_state[name]["x"]
P = self.kalman_state[name]["P"]
Z = current_vals[i]
# If this is the first reading, initialize
if x is None or P is None:
x = Z
P = 1.0 # or some large initial uncertainty
# 1) Predict step
x_pred = x # no velocity model, so x_pred = x
P_pred = P + Q
# 2) Update step
K = P_pred / (P_pred + R) # Kalman gain
x_new = x_pred + K * (Z - x_pred) # new state estimate
P_new = (1 - K) * P_pred # new covariance
# Save back
self.kalman_state[name]["x"] = x_new
self.kalman_state[name]["P"] = P_new
filtered_vals[i] = x_new
if self.calibration is not None:
filtered_vals = self.apply_calibration(filtered_vals, motor_names)
return filtered_vals
def async_read(self):
"""
Continuously read from the serial buffer in its own thread,
store into `self.last_d` and also append to the rolling buffer (joint_buffer).
"""
while True:
if self.serial.in_waiting > 0:
self.serial.flush()
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
if len(vals) != 7:
continue
try:
vals = [int(val) for val in vals]#remove last digit
except ValueError:
self.serial.flush()
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
vals = [int(val) for val in vals]
d = {
"wrist_roll": vals[0],
"wrist_yaw": vals[1],
"wrist_pitch": vals[2],
"elbow_flex": vals[3],
"shoulder_roll": vals[4],
"shoulder_yaw": vals[5],
"shoulder_pitch": vals[6],
}
# Update the last_d dictionary
self.last_d = d
# Also push these new values into the rolling buffers
for joint_name, joint_val in d.items():
self.joint_buffer[joint_name].append(joint_val)
# Optional: short sleep to avoid busy-loop
# time.sleep(0.001)
def run_calibration(self, robot):
robot.arm_bus.write("Acceleration", 50)
n_joints = len(self.joint_names)
max_open_all = np.zeros(n_joints, dtype=np.float32)
min_open_all = np.zeros(n_joints, dtype=np.float32)
max_closed_all = np.zeros(n_joints, dtype=np.float32)
min_closed_all = np.zeros(n_joints, dtype=np.float32)
for i, jname in enumerate(self.joint_names):
print(f"\n--- Calibrating joint '{jname}' ---")
joint_idx = robot.arm_calib_dict["motor_names"].index(jname)
open_val = robot.arm_calib_dict["start_pos"][joint_idx]
print(f"Commanding {jname} to OPEN position {open_val}...")
robot.arm_bus.write("Goal_Position", [open_val], [jname])
input("Physically verify or adjust the joint. Press Enter when ready to capture...")
open_pos_list = []
for _ in range(100):
all_joints_vals = self.read() # read entire arm
open_pos_list.append(all_joints_vals[i]) # store only this joint
time.sleep(0.01)
# Convert to numpy and track min/max
open_array = np.array(open_pos_list, dtype=np.float32)
max_open_all[i] = open_array.max()
min_open_all[i] = open_array.min()
closed_val = robot.arm_calib_dict["end_pos"][joint_idx]
if jname == "elbow_flex":
closed_val = closed_val - 700
closed_val = robot.arm_calib_dict["end_pos"][joint_idx]
print(f"Commanding {jname} to CLOSED position {closed_val}...")
robot.arm_bus.write("Goal_Position", [closed_val], [jname])
input("Physically verify or adjust the joint. Press Enter when ready to capture...")
closed_pos_list = []
for _ in range(100):
all_joints_vals = self.read()
closed_pos_list.append(all_joints_vals[i])
time.sleep(0.01)
closed_array = np.array(closed_pos_list, dtype=np.float32)
# Some thresholding for closed positions
#closed_array[closed_array < 1000] = 60000
max_closed_all[i] = closed_array.max()
min_closed_all[i] = closed_array.min()
robot.arm_bus.write("Goal_Position", [int((closed_val+open_val)/2)], [jname])
open_pos = np.maximum(max_open_all, max_closed_all)
closed_pos = np.minimum(min_open_all, min_closed_all)
for i, jname in enumerate(self.joint_names):
if jname not in ["wrist_pitch", "shoulder_pitch"]:
# Swap open/closed for these joints
tmp_pos = open_pos[i]
open_pos[i] = closed_pos[i]
closed_pos[i] = tmp_pos
# Debug prints
print("\nFinal open/closed arrays after any swaps/inversions:")
print(f"open_pos={open_pos}")
print(f"closed_pos={closed_pos}")
homing_offset = [0] * n_joints
drive_mode = [0] * n_joints
calib_modes = [CalibrationMode.LINEAR.name] * n_joints
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": open_pos,
"end_pos": closed_pos,
"calib_mode": calib_modes,
"motor_names": self.joint_names,
}
file_path = "examples/hopejr/settings/arm_calib.pkl"
if not os.path.exists(file_path):
with open(file_path, "wb") as f:
pickle.dump(calib_dict, f)
print(f"Dictionary saved to {file_path}")
self.set_calibration(calib_dict)
def set_calibration(self, calibration: dict[str, list]):
self.calibration = calibration
def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
"""
Example calibration that linearly maps [start_pos, end_pos] to [0,100].
Extend or modify for your needs.
"""
if motor_names is None:
motor_names = self.joint_names
values = values.astype(np.float32)
for i, name in enumerate(motor_names):
calib_idx = self.calibration["motor_names"].index(name)
calib_mode = self.calibration["calib_mode"][calib_idx]
if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
start_pos = self.calibration["start_pos"][calib_idx]
end_pos = self.calibration["end_pos"][calib_idx]
# Rescale the present position to [0, 100]
values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
# Check boundaries
if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
# If you want to handle out-of-range differently:
# raise JointOutOfRangeError(msg)
msg = (
f"Wrong motor position range detected for {name}. "
f"Value = {values[i]} %, expected within [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}]"
)
print(msg)
return values
class HomonculusGlove:
def __init__(self, serial_port: str = "/dev/ttyACM1", baud_rate: int = 115200):
self.serial_port = serial_port
self.baud_rate = baud_rate
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
# Number of past values to keep in memory
self.buffer_size = 10
# Initialize a buffer (deque) for each joint
self.joint_buffer = {
"thumb_0": deque(maxlen=self.buffer_size),
"thumb_1": deque(maxlen=self.buffer_size),
"thumb_2": deque(maxlen=self.buffer_size),
"thumb_3": deque(maxlen=self.buffer_size),
"index_0": deque(maxlen=self.buffer_size),
"index_1": deque(maxlen=self.buffer_size),
"index_2": deque(maxlen=self.buffer_size),
"middle_0": deque(maxlen=self.buffer_size),
"middle_1": deque(maxlen=self.buffer_size),
"middle_2": deque(maxlen=self.buffer_size),
"ring_0": deque(maxlen=self.buffer_size),
"ring_1": deque(maxlen=self.buffer_size),
"ring_2": deque(maxlen=self.buffer_size),
"pinky_0": deque(maxlen=self.buffer_size),
"pinky_1": deque(maxlen=self.buffer_size),
"pinky_2": deque(maxlen=self.buffer_size),
"battery_voltage": deque(maxlen=self.buffer_size),
}
# Start the reading thread
self.thread = threading.Thread(target=self.async_read, daemon=True)
self.thread.start()
# Last read dictionary
self.last_d = {
"thumb_0": 100,
"thumb_1": 100,
"thumb_2": 100,
"thumb_3": 100,
"index_0": 100,
"index_1": 100,
"index_2": 100,
"middle_0": 100,
"middle_1": 100,
"middle_2": 100,
"ring_0": 100,
"ring_1": 100,
"ring_2": 100,
"pinky_0": 100,
"pinky_1": 100,
"pinky_2": 100,
"battery_voltage": 100,
}
self.calibration = None
@property
def joint_names(self):
return list(self.last_d.keys())
def read(self, motor_names: list[str] | None = None):
"""
Return the most recent (single) values from self.last_d,
optionally applying calibration.
"""
if motor_names is None:
motor_names = self.joint_names
# Get raw (last) values
values = np.array([self.last_d[k] for k in motor_names])
print(values)
# Apply calibration if available
if self.calibration is not None:
values = self.apply_calibration(values, motor_names)
print(values)
return values
def read_running_average(self, motor_names: list[str] | None = None, linearize=False):
"""
Return the AVERAGE of the most recent self.buffer_size (or fewer, if not enough data) readings
for each joint, optionally applying calibration.
"""
if motor_names is None:
motor_names = self.joint_names
# Gather averaged readings from buffers
smoothed_vals = []
for name in motor_names:
buf = self.joint_buffer[name]
if len(buf) == 0:
# If no data has been read yet, fall back to last_d
smoothed_vals.append(self.last_d[name])
else:
# Otherwise, average over the existing buffer
smoothed_vals.append(np.mean(buf))
smoothed_vals = np.array(smoothed_vals, dtype=np.float32)
# Apply calibration if available
if self.calibration is not None:
smoothed_vals = self.apply_calibration(smoothed_vals, motor_names)
return smoothed_vals
def async_read(self):
"""
Continuously read from the serial buffer in its own thread,
store into `self.last_d` and also append to the rolling buffer (joint_buffer).
"""
while True:
if self.serial.in_waiting > 0:
self.serial.flush()
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
if len(vals) != 17:
continue
vals = [int(val) for val in vals]
d = {
"thumb_0": vals[0],
"thumb_1": vals[1],
"thumb_2": vals[2],
"thumb_3": vals[3],
"index_0": vals[4],
"index_1": vals[5],
"index_2": vals[6],
"middle_0": vals[7],
"middle_1": vals[8],
"middle_2": vals[9],
"ring_0": vals[10],
"ring_1": vals[11],
"ring_2": vals[12],
"pinky_0": vals[13],
"pinky_1": vals[14],
"pinky_2": vals[15],
"battery_voltage": vals[16],
}
# Update the last_d dictionary
self.last_d = d
# Also push these new values into the rolling buffers
for joint_name, joint_val in d.items():
self.joint_buffer[joint_name].append(joint_val)
def run_calibration(self):
print("\nMove arm to open position")
input("Press Enter to continue...")
open_pos_list = []
for _ in range(100):
open_pos = self.read()
open_pos_list.append(open_pos)
time.sleep(0.01)
open_pos = np.array(open_pos_list)
max_open_pos = open_pos.max(axis=0)
min_open_pos = open_pos.min(axis=0)
print(f"{max_open_pos=}")
print(f"{min_open_pos=}")
print("\nMove arm to closed position")
input("Press Enter to continue...")
closed_pos_list = []
for _ in range(100):
closed_pos = self.read()
closed_pos_list.append(closed_pos)
time.sleep(0.01)
closed_pos = np.array(closed_pos_list)
max_closed_pos = closed_pos.max(axis=0)
closed_pos[closed_pos < 1000] = 60000
min_closed_pos = closed_pos.min(axis=0)
print(f"{max_closed_pos=}")
print(f"{min_closed_pos=}")
open_pos = np.array([max_open_pos, max_closed_pos]).max(axis=0)
closed_pos = np.array([min_open_pos, min_closed_pos]).min(axis=0)
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
for i, jname in enumerate(self.joint_names):
if jname in [
"thumb_0",
"thumb_3",
"index_2",
"middle_2",
"ring_2",
"pinky_2",
"index_0",
]:
tmp_pos = open_pos[i]
open_pos[i] = closed_pos[i]
closed_pos[i] = tmp_pos
print()
print(f"{open_pos=}")
print(f"{closed_pos=}")
homing_offset = [0] * len(self.joint_names)
drive_mode = [0] * len(self.joint_names)
calib_modes = [CalibrationMode.LINEAR.name] * len(self.joint_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": open_pos,
"end_pos": closed_pos,
"calib_mode": calib_modes,
"motor_names": self.joint_names,
}
file_path = "examples/hopejr/settings/hand_calib.pkl"
if not os.path.exists(file_path):
with open(file_path, "wb") as f:
pickle.dump(calib_dict, f)
print(f"Dictionary saved to {file_path}")
# return calib_dict
self.set_calibration(calib_dict)
def set_calibration(self, calibration: dict[str, list]):
self.calibration = calibration
def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
"""Convert from unsigned int32 joint position range [0, 2**32[ to the universal float32 nominal degree range ]-180.0, 180.0[ with
a "zero position" at 0 degree.
Note: We say "nominal degree range" since the motors can take values outside this range. For instance, 190 degrees, if the motor
rotate more than a half a turn from the zero position. However, most motors can't rotate more than 180 degrees and will stay in this range.
Joints values are original in [0, 2**32[ (unsigned int32). Each motor are expected to complete a full rotation
when given a goal position that is + or - their resolution. For instance, feetech xl330-m077 have a resolution of 4096, and
at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
in the centered nominal degree range ]-180, 180[.
"""
if motor_names is None:
motor_names = self.motor_names
# Convert from unsigned int32 original range [0, 2**32] to signed float32 range
values = values.astype(np.float32)
for i, name in enumerate(motor_names):
calib_idx = self.calibration["motor_names"].index(name)
calib_mode = self.calibration["calib_mode"][calib_idx]
if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
start_pos = self.calibration["start_pos"][calib_idx]
end_pos = self.calibration["end_pos"][calib_idx]
# Rescale the present position to a nominal range [0, 100] %,
# useful for joints with linear motions like Aloha gripper
values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
if name == "pinky_1" and (values[i] < LOWER_BOUND_LINEAR):
values[i] = end_pos
else:
msg = (
f"Wrong motor position range detected for {name}. "
f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
f"but present value is {values[i]} %. "
"This might be due to a cable connection issue creating an artificial jump in motor values. "
"You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
)
print(msg)
# raise JointOutOfRangeError(msg)
return values
# def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
# """Inverse of `apply_calibration`."""
# if motor_names is None:
# motor_names = self.motor_names
# for i, name in enumerate(motor_names):
# calib_idx = self.calibration["motor_names"].index(name)
# calib_mode = self.calibration["calib_mode"][calib_idx]
# if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
# start_pos = self.calibration["start_pos"][calib_idx]
# end_pos = self.calibration["end_pos"][calib_idx]
# # Convert from nominal lnear range of [0, 100] % to
# # actual motor range of values which can be arbitrary.
# values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
# values = np.round(values).astype(np.int32)
# return values
class EncoderReader:
def __init__(self, serial_port="/dev/ttyUSB1", baud_rate=115200):
self.serial_port = serial_port
self.baud_rate = baud_rate
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
# Start a background thread to continuously read from the serial port
self.thread = threading.Thread(target=self.async_read, daemon=True)
self.thread.start()
# Store the latest encoder reading in this dictionary
self.last_d = {"encoder": 500}
def async_read(self):
while True:
# Read one line from serial
line = self.serial.readline().decode("utf-8").strip()
if line:
try:
val = int(line) # Parse the incoming line as integer
self.last_d["encoder"] = val
except ValueError:
# If we couldn't parse it as an integer, just skip
pass
def read(self):
"""
Returns the last encoder value that was read.
"""
return self.last_d["encoder"]
class Tac_Man:
def __init__(self, serial_port="/dev/ttyUSB1", baud_rate=115200):
self.serial_port = serial_port
self.baud_rate = baud_rate
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
# Start a background thread to continuously read from the serial port
self.thread = threading.Thread(target=self.async_read, daemon=True)
self.thread.start()
# Store the latest encoder readings in this list
self.last_d = [0, 0, 0] # Default values for three readings
def async_read(self):
while True:
# Read one line from serial
line = self.serial.readline().decode("utf-8").strip()
if line:
try:
# Parse the incoming line as three comma-separated integers
values = [int(val) for val in line.split(",")]
if len(values) == 3: # Ensure we have exactly three values
self.last_d = values
except ValueError:
# If parsing fails, skip this line
pass
def read(self):
"""
Returns the last encoder values that were read as a list of three integers.
"""
return self.last_d

111
examples/hopejr/notes Normal file
View File

@@ -0,0 +1,111 @@
test and test4
installed serial and opencv
after pip install -e .
pip install -e ".[feetech]"
robot.hand_bus.read("Present_Position")
array([ 349, 799, 1000, 1004, 508, 503, 673, 608, 791, 390, 552,
506, 600, 565, 428, 379], dtype=int32)
robot.hand_bus.write("Goal_Position",[349,799,500,500,508,503,673,608,791,390,552,506,600,565,428,379])
robot.arm_bus.write("Goal_Position", [1825, 2045, 2010, 2035, 1414, 1800, 1615])
robot.arm_bus.read("Present_Position")
robot.arm_bus.write("Goal_Position", [1500], ["elbow_flex"])
robot.arm_bus.write("Goal_Position", [2000], ["wrist_yaw"])
ranges: [600-2300, 1500-2300, 1300-2800, 1000-2500, 600-2800,400-1700, 1300-2300]
shoulder_up,
shoulder forward,
shoulder yaw,
elbow_flex
wrist_yaw,
wrist_pitch,
wrist_roll
COM18
C:/Users/Lenovo/AppData/Local/Programs/Python/Python310/python.exe c:/Users/Lenovo/Documents/HuggingFace/lerobot/examples/test4.py
wrist pitch is fucked
so the wrist motor was fucked
and we didnt know which one it was because
if the chain hjas an issue we dont know how to locate whihc motor is at fault (cables are hard to remove)
to calibrate:
python lerobot/scripts/configure_motor.py \
--port /dev/ttyACM1 \
--brand feetech \
--model sts3250 \
--baudrate 1000000 \
--ID 2
python lerobot/scripts/configure_motor.py \
--port /dev/ttyACM0 \
--brand feetech \
--model sm8512bl \
--baudrate 115200 \
--ID 1
python lerobot/scripts/configure_motor.py \
--port /dev/ttyACM1 \
--brand feetech \
--model scs0009 \
--baudrate 1000000 \
--ID 30
why are the motors beeping?
#interpolate between start and end pos
robot.arm_bus.write("Goal_Position", [int((i*interp+j*(1-interp))) for i, j in zip(arm_calibration["start_pos"], arm_calibration["end_pos"])])
control maj M to look for stuff
set calibration is useless
move the joints to that position too
/home/nepyope/Desktop/HuggingFace/lerobot/lerobot/common/robot_devices/motors/feetech.py
theres clearly some lag, and its probably because of an out of range issue
# hand_calibration = robot.get_hand_calibration()
# joint = input("Enter joint name: ")
# j1 = f"{joint}_pinky_side"
# j2 = f"{joint}_thumb_side"
# encoder = EncoderReader("/dev/ttyUSB0", 115200)
# start_angle1 = hand_calibration['start_pos'][hand_calibration['motor_names'].index(j1)]
# end_angle1 = hand_calibration['end_pos'][hand_calibration['motor_names'].index(j1)]
# start_angle2 = hand_calibration['start_pos'][hand_calibration['motor_names'].index(j2)]
# end_angle2 = hand_calibration['end_pos'][hand_calibration['motor_names'].index(j2)]
# # start_angle = shoulder_calibration['start_pos'][shoulder_calibration['motor_names'].index(joint)]
# # end_angle = shoulder_calibration['end_pos'][shoulder_calibration['motor_names'].index(joint)]
# while True:
# angle1 = int(start_angle1+(end_angle1-start_angle1)*encoder.read()/1000)
# angle2 = int(start_angle2+(end_angle2-start_angle2)*encoder.read()/1000)
# robot.hand_bus.write("Goal_Position",angle1, [j1])
# robot.hand_bus.write("Goal_Position",angle2, [j2])
# print(angle1, angle2)
# time.sleep(0.1)
# print(robot.hand_bus.find_motor_indices())
# exit()
maybe divide the 3.3 by 2 and use that as a reference
https://jlcpcb.com/partdetail/23831236-OPA340UA_UMW/C22365307
-90 is good for the op amp

52
examples/hopejr/read.cs Normal file
View File

@@ -0,0 +1,52 @@
#include <Arduino.h>
// Define multiplexer input pins
#define S0 5
#define S1 6
#define S2 8
#define S3 7
#define SENSOR_INPUT 4
#define SENSOR_COUNT 16
int rawVals[SENSOR_COUNT];
void measureRawValues() {
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
digitalWrite(S0, (i & 0b1) ^ 0b1);;
digitalWrite(S1, (i >> 1 & 0b1) ^ 0b1);;
digitalWrite(S2, (i >> 2 & 0b1) ^ 0b1);;
digitalWrite(S3, i >> 3 & 0b1);
delay(1);
rawVals[i] = analogRead(SENSOR_INPUT);
}
}
void printRawValues() {
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
Serial.print(rawVals[i]);
if (i < SENSOR_COUNT - 1) Serial.print(" ");
}
Serial.println();
}
void setup() {
Serial.begin(115200);
pinMode(S0, OUTPUT);
pinMode(S1, OUTPUT);
pinMode(S2, OUTPUT);
pinMode(S3, OUTPUT);
digitalWrite(S0, LOW);
digitalWrite(S1, LOW);
digitalWrite(S2, LOW);
digitalWrite(S3, LOW);
}
void loop() {
measureRawValues();
printRawValues();
delay(1);
}

View File

@@ -0,0 +1,52 @@
#include <Arduino.h>
// Define multiplexer input pins
#define S0 5
#define S1 6
#define S2 8
#define S3 7
#define SENSOR_INPUT 4
#define SENSOR_COUNT 16
int rawVals[SENSOR_COUNT];
void measureRawValues() {
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
digitalWrite(S0, (i & 0b1) ^ 0b1);;
digitalWrite(S1, (i >> 1 & 0b1) ^ 0b1);;
digitalWrite(S2, (i >> 2 & 0b1) ^ 0b1);;
digitalWrite(S3, i >> 3 & 0b1);
delay(1);
rawVals[i] = analogRead(SENSOR_INPUT);
}
}
void printRawValues() {
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
Serial.print(rawVals[i]);
if (i < SENSOR_COUNT - 1) Serial.print(" ");
}
Serial.println();
}
void setup() {
Serial.begin(115200);
pinMode(S0, OUTPUT);
pinMode(S1, OUTPUT);
pinMode(S2, OUTPUT);
pinMode(S3, OUTPUT);
digitalWrite(S0, LOW);
digitalWrite(S1, LOW);
digitalWrite(S2, LOW);
digitalWrite(S3, LOW);
}
void loop() {
measureRawValues();
printRawValues();
delay(1);
}

View File

@@ -0,0 +1,52 @@
#include <Arduino.h>
// Define multiplexer input pins
#define S0 5
#define S1 6
#define S2 8
#define S3 7
#define SENSOR_INPUT 4
#define SENSOR_COUNT 16
int rawVals[SENSOR_COUNT];
void measureRawValues() {
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
digitalWrite(S0, (i & 0b1) ^ 0b1);;
digitalWrite(S1, (i >> 1 & 0b1) ^ 0b1);;
digitalWrite(S2, (i >> 2 & 0b1) ^ 0b1);;
digitalWrite(S3, i >> 3 & 0b1);
delay(1);
rawVals[i] = analogRead(SENSOR_INPUT);
}
}
void printRawValues() {
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
Serial.print(rawVals[i]);
if (i < SENSOR_COUNT - 1) Serial.print(" ");
}
Serial.println();
}
void setup() {
Serial.begin(115200);
pinMode(S0, OUTPUT);
pinMode(S1, OUTPUT);
pinMode(S2, OUTPUT);
pinMode(S3, OUTPUT);
digitalWrite(S0, LOW);
digitalWrite(S1, LOW);
digitalWrite(S2, LOW);
digitalWrite(S3, LOW);
}
void loop() {
measureRawValues();
printRawValues();
delay(1);
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 75 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.2 KiB

View File

@@ -0,0 +1,74 @@
import numpy as np
from PIL import Image, ImageSequence
def coalesce_gif(im):
"""
Attempt to coalesce frames so each one is a full image.
This handles many (though not all) partial-frame GIFs.
"""
# Convert mode to RGBA
im = im.convert("RGBA")
# Prepare an accumulator the same size as the base frame
base = Image.new("RGBA", im.size)
frames = []
# Go through each frame
for frame in ImageSequence.Iterator(im):
base.alpha_composite(frame.convert("RGBA"))
frames.append(base.copy())
return frames
def remove_white_make_black(arr, threshold=250):
"""
For each pixel in arr (H,W,3), if R,G,B >= threshold, set to black (0,0,0).
This effectively 'removes' white so it won't affect the sum.
"""
mask = (arr[..., 0] >= threshold) & \
(arr[..., 1] >= threshold) & \
(arr[..., 2] >= threshold)
arr[mask] = 0 # set to black
def main():
# Load the animated GIF
gif = Image.open("input.gif")
# Coalesce frames so each is full-size
frames = coalesce_gif(gif)
if not frames:
print("No frames found!")
return
# Convert first frame to RGB array, initialize sum array
w, h = frames[0].size
sum_array = np.zeros((h, w, 3), dtype=np.uint16) # 16-bit to avoid overflow
# For each frame:
for f in frames:
# Convert to RGB
rgb = f.convert("RGB")
arr = np.array(rgb, dtype=np.uint16) # shape (H, W, 3)
# Remove near-white by setting it to black
remove_white_make_black(arr, threshold=250)
# Add to sum_array, then clamp to 255
sum_array += arr
np.clip(sum_array, 0, 255, out=sum_array)
# Convert sum_array back to 8-bit
sum_array = sum_array.astype(np.uint8)
# Finally, any pixel that stayed black is presumably "empty," so we set it to white
black_mask = (sum_array[..., 0] == 0) & \
(sum_array[..., 1] == 0) & \
(sum_array[..., 2] == 0)
sum_array[black_mask] = [255, 255, 255]
# Create final Pillow image
final_img = Image.fromarray(sum_array, mode="RGB")
final_img.save("result.png")
print("Done! Wrote result.png.")
if __name__ == "__main__":
main()

View File

@@ -0,0 +1,31 @@
import time
import serial
import numpy as np
import matplotlib.pyplot as plt
# Import the motor bus (adjust the import path as needed)
from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus
def main():
bus = FeetechMotorsBus(
port="/dev/ttyACM0",
motors={
"leader": [1, "scs0009"],
"follower": [2, "scs0009"]
},
protocol_version=1,
group_sync_read=False
)
bus.connect()
print(bus.read("Present_Position", "leader"))
bus.write("Torque_Enable", 0, ["leader"])
bus.write("Torque_Enable", 1, ["follower"])
for i in range(10000000):
time.sleep(0.01)
pos = bus.read("Present_Position", "leader")
if pos[0] > 1 and pos[0] < 1022:
bus.write("Goal_Position", pos, ["follower"])
if __name__ == "__main__":
main()

Binary file not shown.

View File

@@ -0,0 +1,15 @@
robot:
arm_bus:
Lock: 0
Torque_Limit: 1000
Protection_Current: 500
Over_Current_Protection_Time: 10
Max_Torque_Limit: 1000
Overload_Torque: 40 # Play around with this
Protection_Time: 1000 # When does it kick in?
Protective_Torque: 1
Maximum_Acceleration: 100
Torque_Enable: 1
Acceleration: 30
hand_bus:
Acceleration: 100

Binary file not shown.

View File

@@ -0,0 +1,61 @@
import time
import numpy as np
from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus
def main():
# Instantiate the bus for a single motor on port /dev/ttyACM0.
arm_bus = FeetechMotorsBus(
port="/dev/ttyACM0",
motors={"wrist_pitch": [1, "scs0009"]},
protocol_version=1,
group_sync_read=False, # using individual read calls
)
arm_bus.connect()
# Configure continuous rotation mode.
arm_bus.write("Min_Angle_Limit", 0)
arm_bus.write("Max_Angle_Limit", 1024)
# For model "scs0009", the raw reading runs from 0 to ~1022.
resolution_max = 1022 # use 1022 as the effective maximum raw value
# Read initial raw motor position.
prev_raw = arm_bus.read("Present_Position", ["wrist_pitch"])[0]
print("Initial raw position:", prev_raw)
# Command continuous rotation.
arm_bus.write("Goal_Position", 1024)
# Initialize loop counter.
loops_count = 0
target_effective = 1780
tolerance = 50 # stop when effective position is within ±50 of target
while True:
current_raw = arm_bus.read("Present_Position", ["wrist_pitch"])[0]
# Detect wrap-around: if the previous reading was near the top (>= 1020)
# and current reading is low (< 100), count that as one full loop.
if prev_raw >= 1020 and current_raw < 100:
loops_count += 1
print(f"Wrap detected! loops_count increased to {loops_count}")
# Compute the effective position.
effective_position = loops_count * resolution_max + current_raw
print(f"Raw position: {current_raw} | loops_count: {loops_count} | Effective position: {effective_position}")
# Check if effective position is within tolerance of the target.
if abs(effective_position - target_effective) <= tolerance:
# Command motor to stop by setting the current raw position as goal.
arm_bus.write("Goal_Position", current_raw)
print(f"Target reached (effective position: {effective_position}). Stopping motor at raw position {current_raw}.")
break
prev_raw = current_raw
time.sleep(0.01) # 10 ms delay
time.sleep(1)
arm_bus.disconnect()
if __name__ == "__main__":
main()

226
examples/hopejr/teleop.py Normal file
View File

@@ -0,0 +1,226 @@
from follower import HopeJuniorRobot
from leader import (
HomonculusArm,
HomonculusGlove,
EncoderReader
)
from visualizer import value_to_color
import time
import numpy as np
import pickle
import pygame
import typer
def main(
calibrate_glove: bool = typer.Option(False, "--calibrate-glove", help="Calibrate the glove"),
calibrate_exoskeleton: bool = typer.Option(False, "--calibrate-exoskeleton", help="Calibrate the exoskeleton"),
freeze_fingers: bool = typer.Option(False, "--freeze-fingers", help="Freeze the fingers"),
freeze_arm: bool = typer.Option(False, "--freeze-arm", help="Freeze the arm")):
show_loads: bool = typer.Option(False, "--show-loads", help="Show the loads in a GUI")
robot = HopeJuniorRobot()
robot.connect_hand()
robot.connect_arm()
#read pos
print(robot.hand_bus.read("Present_Position"))
print(robot.arm_bus.read("Present_Position", "shoulder_pitch"))
print(robot.arm_bus.read("Present_Position",["shoulder_yaw","shoulder_roll","elbow_flex","wrist_roll","wrist_yaw","wrist_pitch"]))
#robot.arm_bus.write("Goal_Position", robot.arm_calib_dict["start_pos"][0]*1 +robot.arm_calib_dict["end_pos"][0]*0, ["wrist_roll"])
for i in range(10):
time.sleep(0.1)
robot.apply_arm_config('examples/hopejr/settings/config.yaml')
# #calibrate arm
arm_calibration = robot.get_arm_calibration()
exoskeleton = HomonculusArm(serial_port="/dev/tty.usbmodem1201")
if calibrate_exoskeleton:
exoskeleton.run_calibration(robot)
file_path = "examples/hopejr/settings/arm_calib.pkl"
with open(file_path, "rb") as f:
calib_dict = pickle.load(f)
print("Loaded dictionary:", calib_dict)
exoskeleton.set_calibration(calib_dict)
#calibrate hand
hand_calibration = robot.get_hand_calibration()
glove = HomonculusGlove(serial_port = "/dev/tty.usbmodem1101")
if calibrate_glove:
glove.run_calibration()
file_path = "examples/hopejr/settings/hand_calib.pkl"
with open(file_path, "rb") as f:
calib_dict = pickle.load(f)
print("Loaded dictionary:", calib_dict)
glove.set_calibration(calib_dict)
robot.hand_bus.set_calibration(hand_calibration)
robot.arm_bus.set_calibration(arm_calibration)
# Initialize Pygame
# pygame.init()
# # Set up the display
# screen = pygame.display.set_mode((800, 600))
# pygame.display.set_caption("Robot Hand Visualization")
# # Create hand structure with 16 squares and initial values
# hand_components = []
# # Add thumb (4 squares in diamond shape)
# thumb_positions = [
# (150, 300), (125, 350),
# (175, 350), (150, 400)
# ]
# for pos in thumb_positions:
# hand_components.append({"pos": pos, "value": 0})
# # Add fingers (4 fingers with 3 squares each in vertical lines)
# finger_positions = [
# (200, 100), # Index
# (250, 100), # Middle
# (300, 100), # Ring
# (350, 100) # Pinky
# ]
# for x, y in finger_positions:
# for i in range(3):
# hand_components.append({"pos": (x, y + i * 50), "value": 0})
for i in range(1000000000000000):
robot.apply_arm_config('examples/hopejr/settings/config.yaml')
#robot.arm_bus.write("Acceleration", 50, "shoulder_yaw")
joint_names = ["shoulder_pitch", "shoulder_yaw", "shoulder_roll", "elbow_flex", "wrist_roll", "wrist_yaw", "wrist_pitch"]
#only wrist roll
#joint_names = ["shoulder_pitch"]
joint_values = exoskeleton.read(motor_names=joint_names)
#joint_values = joint_values.round().astype(int)
joint_dict = {k: v for k, v in zip(joint_names, joint_values, strict=False)}
motor_values = []
motor_names = []
motor_names += ["shoulder_pitch", "shoulder_yaw", "shoulder_roll", "elbow_flex", "wrist_roll", "wrist_yaw", "wrist_pitch"]
#motor_names += ["shoulder_pitch"]
motor_values += [joint_dict[name] for name in motor_names]
#remove 50 from shoulder_roll
#motor_values += [joint_dict[name] for name in motor_names]
motor_values = np.array(motor_values)
motor_values = np.clip(motor_values, 0, 100)
print(motor_names, motor_values)
if not freeze_arm:
robot.arm_bus.write("Goal_Position", motor_values, motor_names)
if not freeze_fingers:#include hand
hand_joint_names = []
hand_joint_names += ["thumb_3", "thumb_2", "thumb_1", "thumb_0"]#, "thumb_3"]
hand_joint_names += ["index_0", "index_1", "index_2"]
hand_joint_names += ["middle_0", "middle_1", "middle_2"]
hand_joint_names += ["ring_0", "ring_1", "ring_2"]
hand_joint_names += ["pinky_0", "pinky_1", "pinky_2"]
hand_joint_values = glove.read(hand_joint_names)
hand_joint_values = hand_joint_values.round( ).astype(int)
hand_joint_dict = {k: v for k, v in zip(hand_joint_names, hand_joint_values, strict=False)}
hand_motor_values = []
hand_motor_names = []
# Thumb
hand_motor_names += ["thumb_basel_rotation", "thumb_mcp", "thumb_pip", "thumb_dip"]#, "thumb_MCP"]
hand_motor_values += [
hand_joint_dict["thumb_3"],
hand_joint_dict["thumb_2"],
hand_joint_dict["thumb_1"],
hand_joint_dict["thumb_0"]
]
# # Index finger
index_splay = 0.1
hand_motor_names += ["index_flexor", "index_pinky_side", "index_thumb_side"]
hand_motor_values += [
hand_joint_dict["index_2"],
(100 - hand_joint_dict["index_0"]) * index_splay + hand_joint_dict["index_1"] * (1 - index_splay),
hand_joint_dict["index_0"] * index_splay + hand_joint_dict["index_1"] * (1 - index_splay),
]
# Middle finger
middle_splay = 0.1
hand_motor_names += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
hand_motor_values += [
hand_joint_dict["middle_2"],
hand_joint_dict["middle_0"] * middle_splay + hand_joint_dict["middle_1"] * (1 - middle_splay),
(100 - hand_joint_dict["middle_0"]) * middle_splay + hand_joint_dict["middle_1"] * (1 - middle_splay),
]
# # Ring finger
ring_splay = 0.1
hand_motor_names += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
hand_motor_values += [
hand_joint_dict["ring_2"],
(100 - hand_joint_dict["ring_0"]) * ring_splay + hand_joint_dict["ring_1"] * (1 - ring_splay),
hand_joint_dict["ring_0"] * ring_splay + hand_joint_dict["ring_1"] * (1 - ring_splay),
]
# # Pinky finger
pinky_splay = -.1
hand_motor_names += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
hand_motor_values += [
hand_joint_dict["pinky_2"],
hand_joint_dict["pinky_0"] * pinky_splay + hand_joint_dict["pinky_1"] * (1 - pinky_splay),
(100 - hand_joint_dict["pinky_0"]) * pinky_splay + hand_joint_dict["pinky_1"] * (1 - pinky_splay),
]
hand_motor_values = np.array(hand_motor_values)
hand_motor_values = np.clip(hand_motor_values, 0, 100)
robot.hand_bus.write("Acceleration", 255, hand_motor_names)
robot.hand_bus.write("Goal_Position", hand_motor_values, hand_motor_names)
# if i%20==0 and i > 100:
# try:
# loads = robot.hand_bus.read("Present_Load")
# for i, comp in enumerate(hand_components):
# # Wave oscillates between 0 and 2024:
# # Center (1012) +/- 1012 * sin(...)
# comp["value"] = loads[i]
# except:
# pass
time.sleep(0.01)
# for event in pygame.event.get():
# if event.type == pygame.QUIT:
# robot.hand_bus.disconnect()
# robot.arm_bus.disconnect()
# exit()
# # Check for user pressing 'q' to quit
# if event.type == pygame.KEYDOWN:
# if event.key == pygame.K_q:
# robot.hand_bus.disconnect()
# robot.arm_bus.disconnect()
# exit()
# # Draw background
# screen.fill((0, 0, 0)) # Black background
# # Draw hand components
# for comp in hand_components:
# x, y = comp["pos"]
# color = value_to_color(comp["value"])
# pygame.draw.rect(screen, color, (x, y, 30, 30))
# pygame.display.flip()
if __name__ == "__main__":
typer.run(main)

View File

@@ -0,0 +1,135 @@
import serial
import threading
import time
import numpy as np
import matplotlib.pyplot as plt
# Thread function to read from a serial port continuously until stop_event is set.
def read_serial(port, baudrate, stop_event, data_list):
try:
ser = serial.Serial(port, baudrate, timeout=1)
except Exception as e:
print(f"Error opening {port}: {e}")
return
while not stop_event.is_set():
try:
line = ser.readline().decode('utf-8').strip()
except Exception as e:
print(f"Decode error on {port}: {e}")
continue
if line:
try:
# Split the line into integer values.
values = [int(x) for x in line.split()]
# For ACM1, ignore the extra value if present.
if len(values) >= 16:
if len(values) > 16:
values = values[:16]
# Save the timestamp (relative to start) with the sensor readings.
timestamp = time.time()
data_list.append((timestamp, values))
except Exception as e:
print(f"Error parsing line from {port}: '{line}' -> {e}")
ser.close()
def main():
# --- Configuration ---
# Set your serial port names here (adjust for your system)
acm0_port = "/dev/ttyACM0" # Example for Linux (or "COM3" on Windows)
acm1_port = "/dev/ttyACM1" # Example for Linux (or "COM4" on Windows)
baudrate = 115200
# Data storage for each device:
data_acm0 = [] # Will hold tuples of (timestamp, [16 sensor values])
data_acm1 = []
# Event to signal threads to stop reading.
stop_event = threading.Event()
# Create and start reader threads.
thread_acm0 = threading.Thread(target=read_serial, args=(acm0_port, baudrate, stop_event, data_acm0))
thread_acm1 = threading.Thread(target=read_serial, args=(acm1_port, baudrate, stop_event, data_acm1))
thread_acm0.start()
thread_acm1.start()
# Record data for 10 seconds.
record_duration = 10 # seconds
start_time = time.time()
time.sleep(record_duration)
stop_event.set() # signal threads to stop
# Wait for both threads to finish.
thread_acm0.join()
thread_acm1.join()
print("Finished recording.")
# --- Process the Data ---
# Convert lists of (timestamp, values) to numpy arrays.
# Compute time relative to the start of the recording.
times_acm0 = np.array([t - start_time for t, _ in data_acm0])
sensor_acm0 = np.array([vals for _, vals in data_acm0]) # shape (N0, 16)
times_acm1 = np.array([t - start_time for t, _ in data_acm1])
sensor_acm1 = np.array([vals for _, vals in data_acm1]) # shape (N1, 16)
# --- Plot 1: Overlapping Time Series ---
plt.figure(figsize=(12, 8))
# Plot each sensor from ACM0 in red.
for i in range(16):
plt.plot(times_acm0, sensor_acm0[:, i], color='red', alpha=0.7,
label='ACM0 Sensor 1' if i == 0 else None)
# Plot each sensor from ACM1 in blue.
for i in range(16):
plt.plot(times_acm1, sensor_acm1[:, i], color='blue', alpha=0.7,
label='ACM1 Sensor 1' if i == 0 else None)
plt.xlabel("Time (s)")
plt.ylabel("Sensor Reading")
plt.title("Overlapping Sensor Readings (ACM0 in Red, ACM1 in Blue)")
plt.legend()
plt.tight_layout()
plt.savefig("overlapping_sensor_readings.png", dpi=300)
plt.close()
print("Saved overlapping_sensor_readings.png")
# --- Plot 2: Variance of Noise for Each Sensor ---
# Compute variance (over time) for each sensor channel.
variance_acm0 = np.var(sensor_acm0, axis=0)
variance_acm1 = np.var(sensor_acm1, axis=0)
sensor_numbers = np.arange(1, 17)
bar_width = 0.35
plt.figure(figsize=(12, 6))
plt.bar(sensor_numbers - bar_width/2, variance_acm0, bar_width, color='red', label='ACM0')
plt.bar(sensor_numbers + bar_width/2, variance_acm1, bar_width, color='blue', label='ACM1')
plt.xlabel("Sensor Number")
plt.ylabel("Variance")
plt.title("Noise Variance per Sensor")
plt.xticks(sensor_numbers)
plt.legend()
plt.tight_layout()
plt.savefig("sensor_variance.png", dpi=300)
plt.close()
print("Saved sensor_variance.png")
# --- Plot 3: Difference Between ACM0 and ACM1 Readings ---
# Since the two devices may not sample at exactly the same time,
# we interpolate ACM1's data onto ACM0's time base for each sensor.
plt.figure(figsize=(12, 8))
for i in range(16):
if len(times_acm1) > 1 and len(times_acm0) > 1:
interp_acm1 = np.interp(times_acm0, times_acm1, sensor_acm1[:, i])
diff = sensor_acm0[:, i] - interp_acm1
plt.plot(times_acm0, diff, label=f"Sensor {i+1}")
plt.xlabel("Time (s)")
plt.ylabel("Difference (ACM0 - ACM1)")
plt.title("Difference in Sensor Readings")
plt.legend(fontsize='small', ncol=2)
plt.tight_layout()
plt.savefig("sensor_differences.png", dpi=300)
plt.close()
print("Saved sensor_differences.png")
if __name__ == "__main__":
main()

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.5 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.3 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 87 KiB

View File

@@ -0,0 +1,84 @@
import time
import serial
import numpy as np
import matplotlib.pyplot as plt
# Import the motor bus (adjust the import path as needed)
from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus
def main():
# -------------------------------
# Setup the motor bus (ACM0)
# -------------------------------
arm_bus = FeetechMotorsBus(
port="/dev/ttyACM0",
motors={
"wrist_pitch": [7, "sts3215"],
},
protocol_version=0,
)
arm_bus.connect()
# -------------------------------
# Setup the serial connection for sensor (ACM1)
# -------------------------------
try:
ser = serial.Serial("/dev/ttyACM1", 115200, timeout=1)
except Exception as e:
print(f"Error opening serial port /dev/ttyACM1: {e}")
return
# Lists to store the motor positions and sensor values.
positions = []
sensor_values = []
# -------------------------------
# Loop: move motor and collect sensor data
# -------------------------------
# We assume that 2800 > 1480 so we decrement by 10 each step.
for pos in range(2800, 1500, -10): # 2800 down to 1480 (inclusive)
# Command the motor to go to position 'pos'
arm_bus.write("Goal_Position", pos, ["wrist_pitch"])
# Wait a short period for the motor to move and the sensor to update.
time.sleep(0.01)
# Read one line from the sensor device.
sensor_val = np.nan # default if reading fails
try:
line = ser.readline().decode('utf-8').strip()
if line:
# Split the line into parts and convert each part to int.
parts = line.split()
# Ensure there are enough values (we expect at least 15 values)
if len(parts) >= 15:
values = [int(x) for x in parts]
# Use the 15th value (index 14)
sensor_val = values[14]
except Exception as e:
print(f"Error parsing sensor data: {e}")
positions.append(pos)
sensor_values.append(sensor_val)
print(f"Motor pos: {pos} | Sensor 15th value: {sensor_val}")
#move it back to
arm_bus.write("Goal_Position", 2800, ["wrist_pitch"])
# -------------------------------
# Plot the data: Motor Angle vs. Sensor 15th Value
# -------------------------------
plt.figure(figsize=(10, 6))
plt.plot(positions, sensor_values, marker='o', linestyle='-')
plt.xlabel("Motor Angle")
plt.ylabel("Sensor 15th Value")
plt.title("Motor Angle vs Sensor 15th Value")
plt.grid(True)
plt.savefig("asd.png", dpi=300)
plt.close()
print("Plot saved as asd.png")
# Close the serial connection.
ser.close()
if __name__ == "__main__":
main()

682
examples/hopejr/test.py Normal file
View File

@@ -0,0 +1,682 @@
import threading
import time
from typing import Callable
import cv2
import numpy as np
# from qai_hub_models.models.mediapipe_hand.app import MediaPipeHandApp
# from qai_hub_models.models.mediapipe_hand.model import (
# MediaPipeHand,
# )
# from qai_hub_models.utils.image_processing import (
# app_to_net_image_inputs,
# )
from lerobot.common.robot_devices.motors.feetech import (
CalibrationMode,
FeetechMotorsBus,
)
LOWER_BOUND_LINEAR = -100
UPPER_BOUND_LINEAR = 200
import serial
class HomonculusGlove:
def __init__(self):
self.serial_port = "COM10"
self.baud_rate = 115200
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
self.thread = threading.Thread(target=self.async_read)
self.thread.start()
self.last_d = {
"thumb_0": 100,
"thumb_1": 100,
"thumb_2": 100,
"thumb_3": 100,
"index_0": 100,
"index_1": 100,
"index_2": 100,
"middle_0": 100,
"middle_1": 100,
"middle_2": 100,
"ring_0": 100,
"ring_1": 100,
"ring_2": 100,
"pinky_0": 100,
"pinky_1": 100,
"pinky_2": 100,
"battery_voltage": 100,
}
self.calibration = None
@property
def joint_names(self):
return list(self.last_d.keys())
def read(self, motor_names: list[str] | None = None):
if motor_names is None:
motor_names = self.joint_names
values = np.array([self.last_d[k] for k in motor_names])
print(motor_names)
print(values)
if self.calibration is not None:
values = self.apply_calibration(values, motor_names)
print(values)
return values
def async_read(self):
while True:
if self.serial.in_waiting > 0:
self.serial.flush()
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
if len(vals) != 17:
continue
vals = [int(val) for val in vals]
d = {
"thumb_0": vals[0],
"thumb_1": vals[1],
"thumb_2": vals[2],
"thumb_3": vals[3],
"index_0": vals[4],
"index_1": vals[5],
"index_2": vals[6],
"middle_0": vals[7],
"middle_1": vals[8],
"middle_2": vals[9],
"ring_0": vals[10],
"ring_1": vals[11],
"ring_2": vals[12],
"pinky_0": vals[13],
"pinky_1": vals[14],
"pinky_2": vals[15],
"battery_voltage": vals[16],
}
self.last_d = d
# print(d.values())
def run_calibration(self):
print("\nMove arm to open position")
input("Press Enter to continue...")
open_pos_list = []
for _ in range(300):
open_pos = self.read()
open_pos_list.append(open_pos)
time.sleep(0.01)
open_pos = np.array(open_pos_list)
max_open_pos = open_pos.max(axis=0)
min_open_pos = open_pos.min(axis=0)
print(f"{max_open_pos=}")
print(f"{min_open_pos=}")
print("\nMove arm to closed position")
input("Press Enter to continue...")
closed_pos_list = []
for _ in range(300):
closed_pos = self.read()
closed_pos_list.append(closed_pos)
time.sleep(0.01)
closed_pos = np.array(closed_pos_list)
max_closed_pos = closed_pos.max(axis=0)
closed_pos[closed_pos < 1000] = 60000
min_closed_pos = closed_pos.min(axis=0)
print(f"{max_closed_pos=}")
print(f"{min_closed_pos=}")
open_pos = np.array([max_open_pos, max_closed_pos]).max(axis=0)
closed_pos = np.array([min_open_pos, min_closed_pos]).min(axis=0)
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
for i, jname in enumerate(self.joint_names):
if jname in ["thumb_0", "thumb_3", "index_2", "middle_2", "ring_2", "pinky_0", "pinky_2"]:
tmp_pos = open_pos[i]
open_pos[i] = closed_pos[i]
closed_pos[i] = tmp_pos
print()
print(f"{open_pos=}")
print(f"{closed_pos=}")
homing_offset = [0] * len(self.joint_names)
drive_mode = [0] * len(self.joint_names)
calib_modes = [CalibrationMode.LINEAR.name] * len(self.joint_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": open_pos,
"end_pos": closed_pos,
"calib_mode": calib_modes,
"motor_names": self.joint_names,
}
# return calib_dict
self.set_calibration(calib_dict)
def set_calibration(self, calibration: dict[str, list]):
self.calibration = calibration
def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
"""Convert from unsigned int32 joint position range [0, 2**32[ to the universal float32 nominal degree range ]-180.0, 180.0[ with
a "zero position" at 0 degree.
Note: We say "nominal degree range" since the motors can take values outside this range. For instance, 190 degrees, if the motor
rotate more than a half a turn from the zero position. However, most motors can't rotate more than 180 degrees and will stay in this range.
Joints values are original in [0, 2**32[ (unsigned int32). Each motor are expected to complete a full rotation
when given a goal position that is + or - their resolution. For instance, feetech xl330-m077 have a resolution of 4096, and
at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
in the centered nominal degree range ]-180, 180[.
"""
if motor_names is None:
motor_names = self.motor_names
# Convert from unsigned int32 original range [0, 2**32] to signed float32 range
values = values.astype(np.float32)
for i, name in enumerate(motor_names):
calib_idx = self.calibration["motor_names"].index(name)
calib_mode = self.calibration["calib_mode"][calib_idx]
if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
start_pos = self.calibration["start_pos"][calib_idx]
end_pos = self.calibration["end_pos"][calib_idx]
# Rescale the present position to a nominal range [0, 100] %,
# useful for joints with linear motions like Aloha gripper
values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
if name == "pinky_1" and (values[i] < LOWER_BOUND_LINEAR):
values[i] = end_pos
else:
msg = (
f"Wrong motor position range detected for {name}. "
f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
f"but present value is {values[i]} %. "
"This might be due to a cable connection issue creating an artificial jump in motor values. "
"You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
)
print(msg)
# raise JointOutOfRangeError(msg)
return values
# def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
# """Inverse of `apply_calibration`."""
# if motor_names is None:
# motor_names = self.motor_names
# for i, name in enumerate(motor_names):
# calib_idx = self.calibration["motor_names"].index(name)
# calib_mode = self.calibration["calib_mode"][calib_idx]
# if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
# start_pos = self.calibration["start_pos"][calib_idx]
# end_pos = self.calibration["end_pos"][calib_idx]
# # Convert from nominal lnear range of [0, 100] % to
# # actual motor range of values which can be arbitrary.
# values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
# values = np.round(values).astype(np.int32)
# return values
class HopeJuniorRobot:
def __init__(self):
self.arm_bus = FeetechMotorsBus(
port="COM14",
motors={
# "motor1": (2, "sts3250"),
# "motor2": (1, "scs0009"),
"shoulder_pitch": [1, "sts3250"],
"shoulder_yaw": [2, "sts3215"], # TODO: sts3250
"shoulder_roll": [3, "sts3215"], # TODO: sts3250
"elbow_flex": [4, "sts3250"],
"wrist_roll": [5, "sts3215"],
"wrist_yaw": [6, "sts3215"],
"wrist_pitch": [7, "sts3215"],
},
protocol_version=0,
)
self.hand_bus = FeetechMotorsBus(
port="COM15",
motors={
"thumb_basel_rotation": [30, "scs0009"],
"thumb_flexor": [27, "scs0009"],
"thumb_pinky_side": [26, "scs0009"],
"thumb_thumb_side": [28, "scs0009"],
"index_flexor": [25, "scs0009"],
"index_pinky_side": [31, "scs0009"],
"index_thumb_side": [32, "scs0009"],
"middle_flexor": [24, "scs0009"],
"middle_pinky_side": [33, "scs0009"],
"middle_thumb_side": [34, "scs0009"],
"ring_flexor": [21, "scs0009"],
"ring_pinky_side": [36, "scs0009"],
"ring_thumb_side": [35, "scs0009"],
"pinky_flexor": [23, "scs0009"],
"pinky_pinky_side": [38, "scs0009"],
"pinky_thumb_side": [37, "scs0009"],
},
protocol_version=1,
group_sync_read=False,
)
def get_hand_calibration(self):
homing_offset = [0] * len(self.hand_bus.motor_names)
drive_mode = [0] * len(self.hand_bus.motor_names)
start_pos = [
500,
900,
1000,
0,
100,
250,
750,
100,
400,
150,
100,
120,
980,
100,
950,
750,
]
end_pos = [
500 - 250,
900 - 300,
1000 - 550,
0 + 550,
1000,
250 + 700,
750 - 700,
1000,
400 + 700,
150 + 700,
1000,
120 + 700,
980 - 700,
1000,
950 - 700,
750 - 700,
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.hand_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.hand_bus.motor_names,
}
return calib_dict
def connect(self):
self.arm_bus.connect()
#self.hand_bus.connect()
ESCAPE_KEY_ID = 27
def capture_and_display_processed_frames(
frame_processor: Callable[[np.ndarray], np.ndarray],
window_display_name: str,
cap_device: int = 0,
) -> None:
"""
Capture frames from the given input camera device, run them through
the frame processor, and display the outputs in a window with the given name.
User should press Esc to exit.
Inputs:
frame_processor: Callable[[np.ndarray], np.ndarray]
Processes frames.
Input and output are numpy arrays of shape (H W C) with BGR channel layout and dtype uint8 / byte.
window_display_name: str
Name of the window used to display frames.
cap_device: int
Identifier for the camera to use to capture frames.
"""
cv2.namedWindow(window_display_name)
capture = cv2.VideoCapture(cap_device)
if not capture.isOpened():
raise ValueError("Unable to open video capture.")
frame_count = 0
has_frame, frame = capture.read()
while has_frame:
assert isinstance(frame, np.ndarray)
frame_count = frame_count + 1
# mirror frame
frame = np.ascontiguousarray(frame[:, ::-1, ::-1])
# process & show frame
processed_frame = frame_processor(frame)
cv2.imshow(window_display_name, processed_frame[:, :, ::-1])
has_frame, frame = capture.read()
key = cv2.waitKey(1)
if key == ESCAPE_KEY_ID:
break
capture.release()
def main():
robot = HopeJuniorRobot()
robot.connect()
# robot.hand_bus.calibration = None
# breakpoint()
# print(robot.arm_bus.read("Present_Position"))
robot.arm_bus.write("Torque_Enable", 1)
robot.arm_bus.write("Acceleration", 20)
robot.arm_bus.read("Acceleration")
robot.arm_bus.write("Goal_Position", calibration["start_pos"])
exit()
calibration = robot.get_hand_calibration()
robot.arm_bus.write("Goal_Position", calibration["start_pos"])
# robot.hand_bus.write("Goal_Position", calibration["end_pos"][:4], robot.hand_bus.motor_names[:4])
robot.hand_bus.set_calibration(calibration)
lol = 1
# # print(motors_bus.write("Goal_Position", 500))
# print(robot.hand_bus.read("Present_Position"))
# # pos = hand_bus.read("Present_Position")
# # hand_bus.write("Goal_Position", pos[0]+20, hand_bus.motor_names[0])
# # hand_bus.write("Goal_Position", pos[i]+delta, hand_bus.motor_names[i])
# robot.hand_bus.read("Acceleration")
# robot.hand_bus.write("Acceleration", 10)
# sleep = 1
# # robot.hand_bus.write(
# # "Goal_Position", [glove.last_d['index_2']-1500,300,300], ["index_pinky_side", "index_flexor", "index_thumb_side"]
# # )
# #time.sleep(sleep)
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [100, 100, 100], ["index_flexor", "index_pinky_side", "index_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [100, 0, 0], ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [200, 200, 0], ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [200, 100, 600], ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
# )
# time.sleep(sleep)
# breakpoint()
glove = HomonculusGlove()
glove.run_calibration()
# while True:
# joint_names = ["index_1", "index_2"]
# joint_values = glove.read(joint_names)
# print(joint_values)
input()
while True:
joint_names = []
joint_names += ["thumb_0", "thumb_2", "thumb_3"]
joint_names += ["index_1", "index_2"]
joint_names += ["middle_1", "middle_2"]
joint_names += ["ring_1", "ring_2"]
joint_names += ["pinky_1", "pinky_2"]
joint_values = glove.read(joint_names)
joint_values = joint_values.round().astype(int)
joint_dict = {k: v for k, v in zip(joint_names, joint_values, strict=False)}
motor_values = []
motor_names = []
motor_names += ["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"]
motor_values += [
joint_dict["thumb_3"],
joint_dict["thumb_0"],
joint_dict["thumb_2"],
joint_dict["thumb_2"],
]
motor_names += ["index_flexor", "index_pinky_side", "index_thumb_side"]
motor_values += [joint_dict["index_2"], joint_dict["index_1"], joint_dict["index_1"]]
motor_names += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
motor_values += [joint_dict["middle_2"], joint_dict["middle_1"], joint_dict["middle_1"]]
motor_names += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
motor_values += [joint_dict["ring_2"], joint_dict["ring_1"], joint_dict["ring_1"]]
motor_names += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
motor_values += [joint_dict["pinky_2"], joint_dict["pinky_1"], joint_dict["pinky_1"]]
motor_values = np.array(motor_values)
motor_values = np.clip(motor_values, 0, 100)
robot.hand_bus.write("Goal_Position", motor_values, motor_names)
time.sleep(0.02)
while True:
# print(glove.read()['index_2']-1500)
glove_index_flexor = glove.read()["index_2"] - 1500
glove_index_subflexor = glove.read()["index_1"] - 1500
glove_index_side = glove.read()["index_0"] - 2100
vals = [glove_index_flexor, 1000 - (glove_index_subflexor), glove_index_subflexor]
keys = ["index_flexor", "index_pinky_side", "index_thumb_side"]
glove_middle_flexor = glove.read()["middle_2"] - 1500
glove_middle_subflexor = 1000 - (glove.read()["middle_1"] - 1700)
vals += [glove_middle_flexor, glove_middle_subflexor, glove_middle_subflexor - 200]
keys += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
glove_ring_flexor = glove.read()["ring_2"] - 1300
print(glove_ring_flexor)
glove_ring_subflexor = glove.read()["ring_1"] - 1100
vals += [glove_ring_flexor, 1000 - glove_ring_subflexor, glove_ring_subflexor]
keys += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
glove_pinky_flexor = glove.read()["pinky_2"] - 1500
glove_pinky_subflexor = glove.read()["pinky_1"] - 1300
vals += [300 + glove_pinky_flexor, max(1000 - glove_pinky_subflexor - 100, 0), glove_pinky_subflexor]
keys += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
robot.hand_bus.write("Goal_Position", vals, keys)
time.sleep(0.1)
time.sleep(3)
def move_arm(loop=10):
sleep = 1
for i in range(loop):
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1195])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 2195])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1457, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 2357, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 974, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 2674, 1957, 1695])
time.sleep(sleep + 2)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 1632, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 1369, 1632, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 1330, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [2381, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1681, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
def move_hand(loop=10):
sleep = 0.5
for i in range(loop):
robot.hand_bus.write(
"Goal_Position",
[500, 1000, 0, 1000],
["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [100, 100, 100], ["index_flexor", "index_pinky_side", "index_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [100, 1000, 150], ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [200, 200, 0], ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [200, 100, 700], ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[500, 1000 - 250, 0 + 300, 1000 - 200],
["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[100 + 450, 100 + 400, 100 + 400],
["index_flexor", "index_pinky_side", "index_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[100 + 350, 1000 - 450, 150 + 450],
["middle_flexor", "middle_pinky_side", "middle_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[200 + 650, 200 + 350, 0 + 350],
["ring_flexor", "ring_pinky_side", "ring_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[200 + 450, 100 + 400, 700 - 400],
["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"],
)
time.sleep(sleep)
move_hand(3)
move_arm(1)
from concurrent.futures import ThreadPoolExecutor
with ThreadPoolExecutor() as executor:
executor.submit(move_arm)
executor.submit(move_hand)
# initial position
for i in range(3):
robot.hand_bus.write(
"Goal_Position", [500, 1000, 0, 1000, 100, 950, 100, 100, 1000, 150, 200, 200, 0, 200, 100, 700]
)
time.sleep(1)
# for i in range(3):
# robot.hand_bus.write("Goal_Position", [500, 1000-150, 0+250, 1000-150,
# 100+300, 950-250, 100+250,
# 100+200, 1000-300, 150+300,
# 200+500, 200+200, 0+200,
# 200+300, 100+200, 700-200])
# time.sleep(1)
# camera = 0
# score_threshold = 0.95
# iou_threshold = 0.3
# app = MediaPipeHandApp(MediaPipeHand.from_pretrained(), score_threshold, iou_threshold)
# def frame_processor(frame: np.ndarray) -> np.ndarray:
# # Input Prep
# NHWC_int_numpy_frames, NCHW_fp32_torch_frames = app_to_net_image_inputs(frame)
# # Run Bounding Box & Keypoint Detector
# batched_selected_boxes, batched_selected_keypoints = app._run_box_detector(NCHW_fp32_torch_frames)
# # The region of interest ( bounding box of 4 (x, y) corners).
# # list[torch.Tensor(shape=[Num Boxes, 4, 2])],
# # where 2 == (x, y)
# #
# # A list element will be None if there is no selected ROI.
# batched_roi_4corners = app._compute_object_roi(batched_selected_boxes, batched_selected_keypoints)
# # selected landmarks for the ROI (if any)
# # list[torch.Tensor(shape=[Num Selected Landmarks, K, 3])],
# # where K == number of landmark keypoints, 3 == (x, y, confidence)
# #
# # A list element will be None if there is no ROI.
# landmarks_out = app._run_landmark_detector(NHWC_int_numpy_frames, batched_roi_4corners)
# app._draw_predictions(
# NHWC_int_numpy_frames,
# batched_selected_boxes,
# batched_selected_keypoints,
# batched_roi_4corners,
# *landmarks_out,
# )
# return NHWC_int_numpy_frames[0]
# capture_and_display_processed_frames(frame_processor, "QAIHM Mediapipe Hand Demo", camera)
if __name__ == "__main__":
main()

231
examples/hopejr/utils.py Normal file
View File

@@ -0,0 +1,231 @@
#robot.arm_bus.write("Acceleration", [20], ["shoulder_pitch"])
####DEBUGGER####################
# joint = input("Enter joint name: ")
# encoder = EncoderReader("/dev/ttyUSB1", 115200)
# start_angle = arm_calibration['start_pos'][arm_calibration['motor_names'].index(joint)]
# end_angle = arm_calibration['end_pos'][arm_calibration['motor_names'].index(joint)]
# # start_angle = shoulder_calibration['start_pos'][shoulder_calibration['motor_names'].index(joint)]
# # end_angle = shoulder_calibration['end_pos'][shoulder_calibration['motor_names'].index(joint)]
# while True:
# angle = int(start_angle+(end_angle-start_angle)*encoder.read()/1000)
# # robot.shoulder_bus.set_bus_baudrate(115200)
# # robot.shoulder_bus.write("Goal_Position",angle, [joint])
# robot.shoulder_bus.set_bus_baudrate(1000000)
# robot.arm_bus.write("Goal_Position",angle, [joint])
# print(angle)
# time.sleep(0.1)
#####SAFETY CHECKS EXPLAINED#####
#There are two safety checks built-in: one is based on load and the other is based on current.
#Current: if Protection_Current > Present_Current we wait Over_Current_Protection_Time (expressed in ms) and set Torque_Enable to 0
#Load: if Max_Torque_Limit*Overload_Torque (expressed as a percentage) > Present_Load, we wait Protection_Time (expressed in ms
#and set Max_Torque_Limit to Protective_Torque)
#Though we can specify Min-Max_Angle_Limit, Max_Temperature_Limit, Min-Max_Voltage_Limit, no safety checks are implemented for these values
#robot.arm_bus.set_calibration(arm_calibration)
#method 1
# robot.arm_bus.write("Overload_Torque", 80)
# robot.arm_bus.write("Protection_Time", 10)
# robot.arm_bus.write("Protective_Torque", 1)
# robot.arm_bus.write("Protection_Current", 200,["shoulder_pitch"])
# robot.arm_bus.write("Over_Current_Protection_Time", 10)
#method 2
# robot.arm_bus.write("Protection_Current", 500,["shoulder_pitch"])
# robot.arm_bus.write("Over_Current_Protection_Time", 10)
# robot.arm_bus.write("Max_Torque_Limit", 1000)
# robot.arm_bus.write("Overload_Torque", 40)
# robot.arm_bus.write("Protection_Time", 10)
# robot.arm_bus.write("Protective_Torque", 1)
# robot.shoulder_bus.set_bus_baudrate(115200)
# robot.shoulder_bus.write("Goal_Position",2500)
# exit()
######LOGGER####################
# from test_torque.log_and_plot_feetech import log_and_plot_params
# params_to_log = [
# "Protection_Current",
# "Present_Current",
# "Max_Torque_Limit",
# "Protection_Time",
# "Overload_Torque",
# "Present_Load",
# "Present_Position",
# ]
# servo_names = ["shoulder_pitch"]
# servo_data, timestamps = log_and_plot_params(robot.shoulder_bus, params_to_log, servo_names, test_id="shoulder_pitch")
# exit()
#robot.arm_bus.write("Goal_Position",2300, ["shoulder_pitch"])
# dt = 2
# steps = 4
# max_pos = 1500
# min_pos = 2300
# increment = (max_pos - min_pos) / steps
# # Move from min_pos to max_pos in steps
# for i in range(steps + 1): # Include the last step
# current_pos = min_pos + int(i * increment)
# robot.arm_bus.write("Goal_Position", [current_pos], ["shoulder_pitch"])
# time.sleep(dt)
# # Move back from max_pos to min_pos in steps
# for i in range(steps + 1): # Include the last step
# current_pos = max_pos - int(i * increment)
# robot.arm_bus.write("Goal_Position", [current_pos], ["shoulder_pitch"])
# time.sleep(dt)shoulder_pitch
#demo to show how sending a lot of values makes the robt shake
# # Step increment
#
# # Move from min_pos to max_pos in steps
# for i in range(steps + 1): # Include the last step
# current_pos = min_pos + int(i * increment)
# robot.arm_bus.write("Goal_Position", [current_pos], ["elbow_flex"])
# time.sleep(dt)
# # Move back from max_pos to min_pos in steps
# for i in range(steps + 1): # Include the last step
# current_pos = max_pos - int(i * increment)
# robot.arm_bus.write("Goal_Position", [current_pos], ["elbow_flex"])
# time.sleep(dt)
# exit()
#robot.arm_bus.write("Goal_Position", a # shoulder_calibration = robot.get_shoulder_calibration()
# print(shoulder_calibration)m_calibration["start_pos"])
# robot.arm_bus.write("Over_Current_Protection_Time", 50)
# robot.arm_bus.write("Protection_Current", 310, ["shoulder_pitch"])
# robot.arm_bus.write("Overload_Torque", 80, ["shoulder_pitch"])
# robot.arm_bus.write("Protection_Time", 100, ["shoulder_pitch"])
# robot.arm_bus.write("Over_Current_Protection_Time", 50, ["shoulder_pitch"])
# robot.arm_bus.write("Protective_Torque", 20, ["shoulder_pitch"])
# robot.arm_bus.write("Goal_Position", [600],["shoulder_pitch"])
# from test_torque.log_and_plot_feetech import log_and_plot_params
# params_to_log = [
# "Present_Current",
# "Protection_Current",
# "Overload_Torque",
# "Protection_Time",
# "Protective_Torque",
# "Present_Load",
# "Present_Position",
# ]
# servo_names = ["shoulder_pitch"]
#
#robot.arm_bus.write("Goal_Position", arm_calibration["start_pos"])
#robot.hand_bus.set_calibration(hand_calibration)
#interp = 0.3
#robot.arm_bus.write("Goal_Position", [int((i*interp+j*(1-interp))) for i, j in zip(arm_calibration["start_pos"], arm_calibration["end_pos"])])
#exit()
# glove = HomonculusGlove()
# glove.run_calibration()
####GOOD FOR GRASPING
# start_pos = [
# 500,
# 900,
# 500,
# 1000,
# 100,
# 450,#250
# 950,#750
# 100,
# 300,#400
# 50,#150
# 100,
# 120,
# 980,
# 100,
# 950,
# 750,
# ]
# end_pos = [
# start_pos[0] - 400,
# start_pos[1] - 300,
# start_pos[2] + 500,
# start_pos[3] - 50,
# start_pos[4] + 900,
# start_pos[5] + 500,
# start_pos[6] - 500,
# start_pos[7] + 900,
# start_pos[8] + 700,
# start_pos[9] + 700,
# start_pos[10] + 900,
# start_pos[11] + 700,
# start_pos[12] - 700,
# start_pos[13] + 900,
# start_pos[14] - 700,
# start_pos[15] - 700,
# ]
SCS_SERIES_CONTROL_TABLE = {
# "Max_Torque_Limit": (16, 2),
# "Phase": (18, 1),
# "Unloading_Condition": (19, 1),
"Protective_Torque": (37, 1),
"Protection_Time": (38, 1),
#Baud_Rate": (48, 1),
}
def read_and_print_scs_values(robot):
for param_name in SCS_SERIES_CONTROL_TABLE:
value = robot.hand_bus.read(param_name)
print(f"{param_name}: {value}")
motor_1_values = {
"Lock" : 255,
#"Protection_Time": 20#so if you write to these they turn to 0 for some fucking reason. protection time was 100, procetive to
}
# motor_1_values = {
# "Lock": 1,
# "Protection_Time": 100,
# "Protective_Torque": 20,
# "Phase": 1,#thisu is bullshit
# "Unloading_Condition": 32,
# }
#bug in writing to specific values of the scs0009
# Write values to motor 2, there is overload torque there
#ok so i can write, the jittering is because of the overload torque which is still being triggered
#TODO: i have to write a functioining version for the sc009 (or i dont who cares)

View File

@@ -0,0 +1,18 @@
# Color gradient function (0-2024 scaled to 0-10)
def value_to_color(value):
# Clamp the value between 0 and 2024
value = max(0, min(2024, value))
# Scale from [0..2024] to [0..10]
scaled_value = (value / 2024) * 10
# Green to Yellow (scaled_value 0..5), then Yellow to Red (scaled_value 5..10)
if scaled_value <= 5:
r = int(255 * (scaled_value / 5))
g = 255
else:
r = 255
g = int(255 * (1 - (scaled_value - 5) / 5))
b = 0
return (r, g, b)

681
examples/test.py Normal file
View File

@@ -0,0 +1,681 @@
import threading
import time
from typing import Callable
import cv2
import numpy as np
# from qai_hub_models.models.mediapipe_hand.app import MediaPipeHandApp
# from qai_hub_models.models.mediapipe_hand.model import (
# MediaPipeHand,
# )
# from qai_hub_models.utils.image_processing import (
# app_to_net_image_inputs,
# )
from lerobot.common.robot_devices.motors.feetech import (
CalibrationMode,
FeetechMotorsBus,
)
LOWER_BOUND_LINEAR = -100
UPPER_BOUND_LINEAR = 200
import serial
class HomonculusGlove:
def __init__(self):
self.serial_port = "/dev/tty.usbmodem21401"
self.baud_rate = 115200
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
self.thread = threading.Thread(target=self.async_read)
self.thread.start()
self.last_d = {
"thumb_0": 100,
"thumb_1": 100,
"thumb_2": 100,
"thumb_3": 100,
"index_0": 100,
"index_1": 100,
"index_2": 100,
"middle_0": 100,
"middle_1": 100,
"middle_2": 100,
"ring_0": 100,
"ring_1": 100,
"ring_2": 100,
"pinky_0": 100,
"pinky_1": 100,
"pinky_2": 100,
"battery_voltage": 100,
}
self.calibration = None
@property
def joint_names(self):
return list(self.last_d.keys())
def read(self, motor_names: list[str] | None = None):
if motor_names is None:
motor_names = self.joint_names
values = np.array([self.last_d[k] for k in motor_names])
print(motor_names)
print(values)
if self.calibration is not None:
values = self.apply_calibration(values, motor_names)
print(values)
return values
def async_read(self):
while True:
if self.serial.in_waiting > 0:
self.serial.flush()
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
if len(vals) != 17:
continue
vals = [int(val) for val in vals]
d = {
"thumb_0": vals[0],
"thumb_1": vals[1],
"thumb_2": vals[2],
"thumb_3": vals[3],
"index_0": vals[4],
"index_1": vals[5],
"index_2": vals[6],
"middle_0": vals[7],
"middle_1": vals[8],
"middle_2": vals[9],
"ring_0": vals[10],
"ring_1": vals[11],
"ring_2": vals[12],
"pinky_0": vals[13],
"pinky_1": vals[14],
"pinky_2": vals[15],
"battery_voltage": vals[16],
}
self.last_d = d
# print(d.values())
def run_calibration(self):
print("\nMove arm to open position")
input("Press Enter to continue...")
open_pos_list = []
for _ in range(300):
open_pos = self.read()
open_pos_list.append(open_pos)
time.sleep(0.01)
open_pos = np.array(open_pos_list)
max_open_pos = open_pos.max(axis=0)
min_open_pos = open_pos.min(axis=0)
print(f"{max_open_pos=}")
print(f"{min_open_pos=}")
print("\nMove arm to closed position")
input("Press Enter to continue...")
closed_pos_list = []
for _ in range(300):
closed_pos = self.read()
closed_pos_list.append(closed_pos)
time.sleep(0.01)
closed_pos = np.array(closed_pos_list)
max_closed_pos = closed_pos.max(axis=0)
closed_pos[closed_pos < 1000] = 60000
min_closed_pos = closed_pos.min(axis=0)
print(f"{max_closed_pos=}")
print(f"{min_closed_pos=}")
open_pos = np.array([max_open_pos, max_closed_pos]).max(axis=0)
closed_pos = np.array([min_open_pos, min_closed_pos]).min(axis=0)
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
for i, jname in enumerate(self.joint_names):
if jname in ["thumb_0", "thumb_3", "index_2", "middle_2", "ring_2", "pinky_0", "pinky_2"]:
tmp_pos = open_pos[i]
open_pos[i] = closed_pos[i]
closed_pos[i] = tmp_pos
print()
print(f"{open_pos=}")
print(f"{closed_pos=}")
homing_offset = [0] * len(self.joint_names)
drive_mode = [0] * len(self.joint_names)
calib_modes = [CalibrationMode.LINEAR.name] * len(self.joint_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": open_pos,
"end_pos": closed_pos,
"calib_mode": calib_modes,
"motor_names": self.joint_names,
}
# return calib_dict
self.set_calibration(calib_dict)
def set_calibration(self, calibration: dict[str, list]):
self.calibration = calibration
def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
"""Convert from unsigned int32 joint position range [0, 2**32[ to the universal float32 nominal degree range ]-180.0, 180.0[ with
a "zero position" at 0 degree.
Note: We say "nominal degree range" since the motors can take values outside this range. For instance, 190 degrees, if the motor
rotate more than a half a turn from the zero position. However, most motors can't rotate more than 180 degrees and will stay in this range.
Joints values are original in [0, 2**32[ (unsigned int32). Each motor are expected to complete a full rotation
when given a goal position that is + or - their resolution. For instance, feetech xl330-m077 have a resolution of 4096, and
at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
in the centered nominal degree range ]-180, 180[.
"""
if motor_names is None:
motor_names = self.motor_names
# Convert from unsigned int32 original range [0, 2**32] to signed float32 range
values = values.astype(np.float32)
for i, name in enumerate(motor_names):
calib_idx = self.calibration["motor_names"].index(name)
calib_mode = self.calibration["calib_mode"][calib_idx]
if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
start_pos = self.calibration["start_pos"][calib_idx]
end_pos = self.calibration["end_pos"][calib_idx]
# Rescale the present position to a nominal range [0, 100] %,
# useful for joints with linear motions like Aloha gripper
values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
if name == "pinky_1" and (values[i] < LOWER_BOUND_LINEAR):
values[i] = end_pos
else:
msg = (
f"Wrong motor position range detected for {name}. "
f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
f"but present value is {values[i]} %. "
"This might be due to a cable connection issue creating an artificial jump in motor values. "
"You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
)
print(msg)
# raise JointOutOfRangeError(msg)
return values
# def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
# """Inverse of `apply_calibration`."""
# if motor_names is None:
# motor_names = self.motor_names
# for i, name in enumerate(motor_names):
# calib_idx = self.calibration["motor_names"].index(name)
# calib_mode = self.calibration["calib_mode"][calib_idx]
# if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
# start_pos = self.calibration["start_pos"][calib_idx]
# end_pos = self.calibration["end_pos"][calib_idx]
# # Convert from nominal lnear range of [0, 100] % to
# # actual motor range of values which can be arbitrary.
# values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
# values = np.round(values).astype(np.int32)
# return values
class HopeJuniorRobot:
def __init__(self):
self.arm_bus = FeetechMotorsBus(
port="/dev/tty.usbmodem58760429571",
motors={
# "motor1": (2, "sts3250"),
# "motor2": (1, "scs0009"),
"shoulder_pitch": [1, "sts3250"],
"shoulder_yaw": [2, "sts3215"], # TODO: sts3250
"shoulder_roll": [3, "sts3215"], # TODO: sts3250
"elbow_flex": [4, "sts3250"],
"wrist_roll": [5, "sts3215"],
"wrist_yaw": [6, "sts3215"],
"wrist_pitch": [7, "sts3215"],
},
protocol_version=0,
)
self.hand_bus = FeetechMotorsBus(
port="/dev/tty.usbmodem585A0077581",
motors={
"thumb_basel_rotation": [30, "scs0009"],
"thumb_flexor": [27, "scs0009"],
"thumb_pinky_side": [26, "scs0009"],
"thumb_thumb_side": [28, "scs0009"],
"index_flexor": [25, "scs0009"],
"index_pinky_side": [31, "scs0009"],
"index_thumb_side": [32, "scs0009"],
"middle_flexor": [24, "scs0009"],
"middle_pinky_side": [33, "scs0009"],
"middle_thumb_side": [34, "scs0009"],
"ring_flexor": [21, "scs0009"],
"ring_pinky_side": [36, "scs0009"],
"ring_thumb_side": [35, "scs0009"],
"pinky_flexor": [23, "scs0009"],
"pinky_pinky_side": [38, "scs0009"],
"pinky_thumb_side": [37, "scs0009"],
},
protocol_version=1,
group_sync_read=False,
)
def get_hand_calibration(self):
homing_offset = [0] * len(self.hand_bus.motor_names)
drive_mode = [0] * len(self.hand_bus.motor_names)
start_pos = [
500,
900,
1000,
0,
100,
250,
750,
100,
400,
150,
100,
120,
980,
100,
950,
750,
]
end_pos = [
500 - 250,
900 - 300,
1000 - 550,
0 + 550,
1000,
250 + 700,
750 - 700,
1000,
400 + 700,
150 + 700,
1000,
120 + 700,
980 - 700,
1000,
950 - 700,
750 - 700,
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.hand_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.hand_bus.motor_names,
}
return calib_dict
def connect(self):
self.arm_bus.connect()
self.hand_bus.connect()
ESCAPE_KEY_ID = 27
def capture_and_display_processed_frames(
frame_processor: Callable[[np.ndarray], np.ndarray],
window_display_name: str,
cap_device: int = 0,
) -> None:
"""
Capture frames from the given input camera device, run them through
the frame processor, and display the outputs in a window with the given name.
User should press Esc to exit.
Inputs:
frame_processor: Callable[[np.ndarray], np.ndarray]
Processes frames.
Input and output are numpy arrays of shape (H W C) with BGR channel layout and dtype uint8 / byte.
window_display_name: str
Name of the window used to display frames.
cap_device: int
Identifier for the camera to use to capture frames.
"""
cv2.namedWindow(window_display_name)
capture = cv2.VideoCapture(cap_device)
if not capture.isOpened():
raise ValueError("Unable to open video capture.")
frame_count = 0
has_frame, frame = capture.read()
while has_frame:
assert isinstance(frame, np.ndarray)
frame_count = frame_count + 1
# mirror frame
frame = np.ascontiguousarray(frame[:, ::-1, ::-1])
# process & show frame
processed_frame = frame_processor(frame)
cv2.imshow(window_display_name, processed_frame[:, :, ::-1])
has_frame, frame = capture.read()
key = cv2.waitKey(1)
if key == ESCAPE_KEY_ID:
break
capture.release()
def main():
robot = HopeJuniorRobot()
robot.connect()
# robot.hand_bus.calibration = None
# breakpoint()
# print(robot.arm_bus.read("Present_Position"))
robot.arm_bus.write("Torque_Enable", 1)
robot.arm_bus.write("Acceleration", 20)
robot.arm_bus.read("Acceleration")
calibration = robot.get_hand_calibration()
robot.hand_bus.write("Goal_Position", calibration["start_pos"])
# robot.hand_bus.write("Goal_Position", calibration["end_pos"][:4], robot.hand_bus.motor_names[:4])
robot.hand_bus.set_calibration(calibration)
lol = 1
# # print(motors_bus.write("Goal_Position", 500))
# print(robot.hand_bus.read("Present_Position"))
# # pos = hand_bus.read("Present_Position")
# # hand_bus.write("Goal_Position", pos[0]+20, hand_bus.motor_names[0])
# # hand_bus.write("Goal_Position", pos[i]+delta, hand_bus.motor_names[i])
# robot.hand_bus.read("Acceleration")
# robot.hand_bus.write("Acceleration", 10)
# sleep = 1
# # robot.hand_bus.write(
# # "Goal_Position", [glove.last_d['index_2']-1500,300,300], ["index_pinky_side", "index_flexor", "index_thumb_side"]
# # )
# #time.sleep(sleep)
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [100, 100, 100], ["index_flexor", "index_pinky_side", "index_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [100, 0, 0], ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [200, 200, 0], ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [200, 100, 600], ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
# )
# time.sleep(sleep)
# breakpoint()
glove = HomonculusGlove()
glove.run_calibration()
# while True:
# joint_names = ["index_1", "index_2"]
# joint_values = glove.read(joint_names)
# print(joint_values)
input()
while True:
joint_names = []
joint_names += ["thumb_0", "thumb_2", "thumb_3"]
joint_names += ["index_1", "index_2"]
joint_names += ["middle_1", "middle_2"]
joint_names += ["ring_1", "ring_2"]
joint_names += ["pinky_1", "pinky_2"]
joint_values = glove.read(joint_names)
joint_values = joint_values.round().astype(int)
joint_dict = {k: v for k, v in zip(joint_names, joint_values, strict=False)}
motor_values = []
motor_names = []
motor_names += ["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"]
motor_values += [
joint_dict["thumb_3"],
joint_dict["thumb_0"],
joint_dict["thumb_2"],
joint_dict["thumb_2"],
]
motor_names += ["index_flexor", "index_pinky_side", "index_thumb_side"]
motor_values += [joint_dict["index_2"], joint_dict["index_1"], joint_dict["index_1"]]
motor_names += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
motor_values += [joint_dict["middle_2"], joint_dict["middle_1"], joint_dict["middle_1"]]
motor_names += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
motor_values += [joint_dict["ring_2"], joint_dict["ring_1"], joint_dict["ring_1"]]
motor_names += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
motor_values += [joint_dict["pinky_2"], joint_dict["pinky_1"], joint_dict["pinky_1"]]
motor_values = np.array(motor_values)
motor_values = np.clip(motor_values, 0, 100)
robot.hand_bus.write("Goal_Position", motor_values, motor_names)
time.sleep(0.02)
while True:
# print(glove.read()['index_2']-1500)
glove_index_flexor = glove.read()["index_2"] - 1500
glove_index_subflexor = glove.read()["index_1"] - 1500
glove_index_side = glove.read()["index_0"] - 2100
vals = [glove_index_flexor, 1000 - (glove_index_subflexor), glove_index_subflexor]
keys = ["index_flexor", "index_pinky_side", "index_thumb_side"]
glove_middle_flexor = glove.read()["middle_2"] - 1500
glove_middle_subflexor = 1000 - (glove.read()["middle_1"] - 1700)
vals += [glove_middle_flexor, glove_middle_subflexor, glove_middle_subflexor - 200]
keys += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
glove_ring_flexor = glove.read()["ring_2"] - 1300
print(glove_ring_flexor)
glove_ring_subflexor = glove.read()["ring_1"] - 1100
vals += [glove_ring_flexor, 1000 - glove_ring_subflexor, glove_ring_subflexor]
keys += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
glove_pinky_flexor = glove.read()["pinky_2"] - 1500
glove_pinky_subflexor = glove.read()["pinky_1"] - 1300
vals += [300 + glove_pinky_flexor, max(1000 - glove_pinky_subflexor - 100, 0), glove_pinky_subflexor]
keys += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
robot.hand_bus.write("Goal_Position", vals, keys)
time.sleep(0.1)
time.sleep(3)
def move_arm(loop=10):
sleep = 1
for i in range(loop):
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1195])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 2195])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1457, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 2357, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 974, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 2674, 1957, 1695])
time.sleep(sleep + 2)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 1632, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 1369, 1632, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 1330, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [2381, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1681, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
def move_hand(loop=10):
sleep = 0.5
for i in range(loop):
robot.hand_bus.write(
"Goal_Position",
[500, 1000, 0, 1000],
["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [100, 100, 100], ["index_flexor", "index_pinky_side", "index_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [100, 1000, 150], ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [200, 200, 0], ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [200, 100, 700], ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[500, 1000 - 250, 0 + 300, 1000 - 200],
["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[100 + 450, 100 + 400, 100 + 400],
["index_flexor", "index_pinky_side", "index_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[100 + 350, 1000 - 450, 150 + 450],
["middle_flexor", "middle_pinky_side", "middle_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[200 + 650, 200 + 350, 0 + 350],
["ring_flexor", "ring_pinky_side", "ring_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[200 + 450, 100 + 400, 700 - 400],
["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"],
)
time.sleep(sleep)
move_hand(3)
move_arm(1)
from concurrent.futures import ThreadPoolExecutor
with ThreadPoolExecutor() as executor:
executor.submit(move_arm)
executor.submit(move_hand)
# initial position
for i in range(3):
robot.hand_bus.write(
"Goal_Position", [500, 1000, 0, 1000, 100, 950, 100, 100, 1000, 150, 200, 200, 0, 200, 100, 700]
)
time.sleep(1)
# for i in range(3):
# robot.hand_bus.write("Goal_Position", [500, 1000-150, 0+250, 1000-150,
# 100+300, 950-250, 100+250,
# 100+200, 1000-300, 150+300,
# 200+500, 200+200, 0+200,
# 200+300, 100+200, 700-200])
# time.sleep(1)
# camera = 0
# score_threshold = 0.95
# iou_threshold = 0.3
# app = MediaPipeHandApp(MediaPipeHand.from_pretrained(), score_threshold, iou_threshold)
# def frame_processor(frame: np.ndarray) -> np.ndarray:
# # Input Prep
# NHWC_int_numpy_frames, NCHW_fp32_torch_frames = app_to_net_image_inputs(frame)
# # Run Bounding Box & Keypoint Detector
# batched_selected_boxes, batched_selected_keypoints = app._run_box_detector(NCHW_fp32_torch_frames)
# # The region of interest ( bounding box of 4 (x, y) corners).
# # list[torch.Tensor(shape=[Num Boxes, 4, 2])],
# # where 2 == (x, y)
# #
# # A list element will be None if there is no selected ROI.
# batched_roi_4corners = app._compute_object_roi(batched_selected_boxes, batched_selected_keypoints)
# # selected landmarks for the ROI (if any)
# # list[torch.Tensor(shape=[Num Selected Landmarks, K, 3])],
# # where K == number of landmark keypoints, 3 == (x, y, confidence)
# #
# # A list element will be None if there is no ROI.
# landmarks_out = app._run_landmark_detector(NHWC_int_numpy_frames, batched_roi_4corners)
# app._draw_predictions(
# NHWC_int_numpy_frames,
# batched_selected_boxes,
# batched_selected_keypoints,
# batched_roi_4corners,
# *landmarks_out,
# )
# return NHWC_int_numpy_frames[0]
# capture_and_display_processed_frames(frame_processor, "QAIHM Mediapipe Hand Demo", camera)
if __name__ == "__main__":
main()

133
examples/test2.py Normal file
View File

@@ -0,0 +1,133 @@
#!/usr/bin/env python
#
# ********* Ping Example *********
#
#
# Available SCServo model on this example : All models using Protocol SCS
# This example is tested with a SCServo(STS/SMS/SCS), and an URT
# Be sure that SCServo(STS/SMS/SCS) properties are already set as %% ID : 1 / Baudnum : 6 (Baudrate : 1000000)
#
import os
if os.name == "nt":
import msvcrt
def getch():
return msvcrt.getch().decode()
else:
import sys
import termios
import tty
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
def getch():
try:
tty.setraw(sys.stdin.fileno())
ch = sys.stdin.read(1)
finally:
termios.tcsetattr(fd, termios.TCSADRAIN, old_settings)
return ch
from scservo_sdk import * # Uses SCServo SDK library
# Default setting
SCS_ID = 1 # SCServo ID : 1
BAUDRATE = 1000000 # SCServo default baudrate : 1000000
DEVICENAME = "/dev/tty.usbserial-2130" # Check which port is being used on your controller
# ex) Windows: "COM1" Linux: "/dev/ttyUSB0" Mac: "/dev/tty.usbserial-*"
protocol_end = 1 # SCServo bit end(STS/SMS=0, SCS=1)
# Initialize PortHandler instance
# Set the port path
# Get methods and members of PortHandlerLinux or PortHandlerWindows
portHandler = PortHandler(DEVICENAME)
# Initialize PacketHandler instance
# Get methods and members of Protocol
packetHandler = PacketHandler(protocol_end)
# Open port
if portHandler.openPort():
print("Succeeded to open the port")
else:
print("Failed to open the port")
print("Press any key to terminate...")
getch()
quit()
# Set port baudrate
if portHandler.setBaudRate(BAUDRATE):
print("Succeeded to change the baudrate")
else:
print("Failed to change the baudrate")
print("Press any key to terminate...")
getch()
quit()
# Try to ping the SCServo
# Get SCServo model number
scs_model_number, scs_comm_result, scs_error = packetHandler.ping(portHandler, SCS_ID)
if scs_comm_result != COMM_SUCCESS:
print("%s" % packetHandler.getTxRxResult(scs_comm_result))
elif scs_error != 0:
print("%s" % packetHandler.getRxPacketError(scs_error))
else:
print("[ID:%03d] ping Succeeded. SCServo model number : %d" % (SCS_ID, scs_model_number))
ADDR_SCS_PRESENT_POSITION = 56
scs_present_position, scs_comm_result, scs_error = packetHandler.read2ByteTxRx(
portHandler, SCS_ID, ADDR_SCS_PRESENT_POSITION
)
if scs_comm_result != COMM_SUCCESS:
print(packetHandler.getTxRxResult(scs_comm_result))
elif scs_error != 0:
print(packetHandler.getRxPacketError(scs_error))
breakpoint()
scs_present_position = SCS_LOWORD(scs_present_position)
# scs_present_speed = SCS_HIWORD(scs_present_position_speed)
# print("[ID:%03d] PresPos:%03d PresSpd:%03d" % (SCS_ID, scs_present_position, SCS_TOHOST(scs_present_speed, 15)))
print("[ID:%03d] PresPos:%03d" % (SCS_ID, scs_present_position))
groupSyncRead = GroupSyncRead(portHandler, packetHandler, ADDR_SCS_PRESENT_POSITION, 2)
scs_addparam_result = groupSyncRead.addParam(SCS_ID)
if scs_addparam_result != True:
print("[ID:%03d] groupSyncRead addparam failed" % SCS_ID)
quit()
# Syncread present position
scs_comm_result = groupSyncRead.txRxPacket()
if scs_comm_result != COMM_SUCCESS:
print("%s" % packetHandler.getTxRxResult(scs_comm_result))
# Check if groupsyncread data of SCServo#1 is available
scs_getdata_result = groupSyncRead.isAvailable(SCS_ID, ADDR_SCS_PRESENT_POSITION, 2)
if scs_getdata_result == True:
# Get SCServo#1 present position value
scs_present_position = groupSyncRead.getData(SCS_ID, ADDR_SCS_PRESENT_POSITION, 2)
else:
scs_present_position = 0
print("[ID:%03d] groupSyncRead getdata failed" % SCS_ID)
# # Check if groupsyncread data of SCServo#2 is available
# scs_getdata_result = groupSyncRead.isAvailable(SCS2_ID, ADDR_SCS_PRESENT_POSITION, 2)
# if scs_getdata_result == True:
# # Get SCServo#2 present position value
# scs2_present_position_speed = groupSyncRead.getData(SCS2_ID, ADDR_SCS_PRESENT_POSITION, 2)
# else:
# print("[ID:%03d] groupSyncRead getdata failed" % SCS2_ID)
scs_present_position = SCS_LOWORD(scs_present_position)
print("[ID:%03d] PresPos:%03d" % (SCS_ID, scs_present_position))
# Close port
portHandler.closePort()

45
examples/test3.py Normal file
View File

@@ -0,0 +1,45 @@
import serial
class HomonculusGlove:
def __init__(self):
self.serial_port = "/dev/tty.usbmodem1101"
self.baud_rate = 115200
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
def read(self):
while True:
if self.serial.in_waiting > 0:
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
vals = [int(val) for val in vals]
d = {
"thumb_0": vals[0],
"thumb_1": vals[1],
"thumb_2": vals[2],
"thumb_3": vals[3],
"index_0": vals[4],
"index_1": vals[5],
"index_2": vals[6],
"middle_0": vals[7],
"middle_1": vals[8],
"middle_2": vals[9],
"ring_0": vals[10],
"ring_1": vals[11],
"ring_2": vals[12],
"pinky_0": vals[13],
"pinky_1": vals[14],
"pinky_2": vals[15],
}
return d
# if ser.in_waiting > 0:
# line = ser.readline().decode('utf-8').strip()
# print(line)
if __name__ == "__main__":
glove = HomonculusGlove()
d = glove.read()
lol = 1

693
examples/test4.py Normal file
View File

@@ -0,0 +1,693 @@
import threading
import time
from typing import Callable
import cv2
import numpy as np
# from qai_hub_models.models.mediapipe_hand.app import MediaPipeHandApp
# from qai_hub_models.models.mediapipe_hand.model import (
# MediaPipeHand,
# )
# from qai_hub_models.utils.image_processing import (
# app_to_net_image_inputs,
# )
from lerobot.common.robot_devices.motors.feetech import (
CalibrationMode,
FeetechMotorsBus,
)
LOWER_BOUND_LINEAR = -100
UPPER_BOUND_LINEAR = 200
import serial
class HomonculusGlove:
def __init__(self):
self.serial_port = "/dev/tty.usbmodem1401"
self.baud_rate = 115200
self.serial = serial.Serial(self.serial_port, self.baud_rate, timeout=1)
self.thread = threading.Thread(target=self.async_read)
self.thread.start()
self.last_d = {
"thumb_0": 100,
"thumb_1": 100,
"thumb_2": 100,
"thumb_3": 100,
"index_0": 100,
"index_1": 100,
"index_2": 100,
"middle_0": 100,
"middle_1": 100,
"middle_2": 100,
"ring_0": 100,
"ring_1": 100,
"ring_2": 100,
"pinky_0": 100,
"pinky_1": 100,
"pinky_2": 100,
"battery_voltage": 100,
}
self.calibration = None
@property
def joint_names(self):
return list(self.last_d.keys())
def read(self, motor_names: list[str] | None = None):
if motor_names is None:
motor_names = self.joint_names
values = np.array([self.last_d[k] for k in motor_names])
print(motor_names)
print(values)
if self.calibration is not None:
values = self.apply_calibration(values, motor_names)
print(values)
return values
def async_read(self):
while True:
if self.serial.in_waiting > 0:
self.serial.flush()
vals = self.serial.readline().decode("utf-8").strip()
vals = vals.split(" ")
if len(vals) != 17:
continue
vals = [int(val) for val in vals]
d = {
"thumb_0": vals[0],
"thumb_1": vals[1],
"thumb_2": vals[2],
"thumb_3": vals[3],
"index_0": vals[4],
"index_1": vals[5],
"index_2": vals[6],
"middle_0": vals[7],
"middle_1": vals[8],
"middle_2": vals[9],
"ring_0": vals[10],
"ring_1": vals[11],
"ring_2": vals[12],
"pinky_0": vals[13],
"pinky_1": vals[14],
"pinky_2": vals[15],
"battery_voltage": vals[16],
}
self.last_d = d
# print(d.values())
def run_calibration(self):
print("\nMove arm to open position")
input("Press Enter to continue...")
open_pos_list = []
for _ in range(300):
open_pos = self.read()
open_pos_list.append(open_pos)
time.sleep(0.01)
open_pos = np.array(open_pos_list)
max_open_pos = open_pos.max(axis=0)
min_open_pos = open_pos.min(axis=0)
print(f"{max_open_pos=}")
print(f"{min_open_pos=}")
print("\nMove arm to closed position")
input("Press Enter to continue...")
closed_pos_list = []
for _ in range(300):
closed_pos = self.read()
closed_pos_list.append(closed_pos)
time.sleep(0.01)
closed_pos = np.array(closed_pos_list)
max_closed_pos = closed_pos.max(axis=0)
closed_pos[closed_pos < 1000] = 60000
min_closed_pos = closed_pos.min(axis=0)
print(f"{max_closed_pos=}")
print(f"{min_closed_pos=}")
open_pos = np.array([max_open_pos, max_closed_pos]).max(axis=0)
closed_pos = np.array([min_open_pos, min_closed_pos]).min(axis=0)
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
# INVERTION
for i, jname in enumerate(self.joint_names):
if jname in [
"thumb_0",
"thumb_3",
"index_2",
"middle_2",
"ring_2",
"pinky_0",
"pinky_2",
"index_0",
]:
tmp_pos = open_pos[i]
open_pos[i] = closed_pos[i]
closed_pos[i] = tmp_pos
print()
print(f"{open_pos=}")
print(f"{closed_pos=}")
homing_offset = [0] * len(self.joint_names)
drive_mode = [0] * len(self.joint_names)
calib_modes = [CalibrationMode.LINEAR.name] * len(self.joint_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": open_pos,
"end_pos": closed_pos,
"calib_mode": calib_modes,
"motor_names": self.joint_names,
}
# return calib_dict
self.set_calibration(calib_dict)
def set_calibration(self, calibration: dict[str, list]):
self.calibration = calibration
def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
"""Convert from unsigned int32 joint position range [0, 2**32[ to the universal float32 nominal degree range ]-180.0, 180.0[ with
a "zero position" at 0 degree.
Note: We say "nominal degree range" since the motors can take values outside this range. For instance, 190 degrees, if the motor
rotate more than a half a turn from the zero position. However, most motors can't rotate more than 180 degrees and will stay in this range.
Joints values are original in [0, 2**32[ (unsigned int32). Each motor are expected to complete a full rotation
when given a goal position that is + or - their resolution. For instance, feetech xl330-m077 have a resolution of 4096, and
at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
in the centered nominal degree range ]-180, 180[.
"""
if motor_names is None:
motor_names = self.motor_names
# Convert from unsigned int32 original range [0, 2**32] to signed float32 range
values = values.astype(np.float32)
for i, name in enumerate(motor_names):
calib_idx = self.calibration["motor_names"].index(name)
calib_mode = self.calibration["calib_mode"][calib_idx]
if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
start_pos = self.calibration["start_pos"][calib_idx]
end_pos = self.calibration["end_pos"][calib_idx]
# Rescale the present position to a nominal range [0, 100] %,
# useful for joints with linear motions like Aloha gripper
values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
if name == "pinky_1" and (values[i] < LOWER_BOUND_LINEAR):
values[i] = end_pos
else:
msg = (
f"Wrong motor position range detected for {name}. "
f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
f"but present value is {values[i]} %. "
"This might be due to a cable connection issue creating an artificial jump in motor values. "
"You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
)
print(msg)
# raise JointOutOfRangeError(msg)
return values
# def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
# """Inverse of `apply_calibration`."""
# if motor_names is None:
# motor_names = self.motor_names
# for i, name in enumerate(motor_names):
# calib_idx = self.calibration["motor_names"].index(name)
# calib_mode = self.calibration["calib_mode"][calib_idx]
# if CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
# start_pos = self.calibration["start_pos"][calib_idx]
# end_pos = self.calibration["end_pos"][calib_idx]
# # Convert from nominal lnear range of [0, 100] % to
# # actual motor range of values which can be arbitrary.
# values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
# values = np.round(values).astype(np.int32)
# return values
class HopeJuniorRobot:
def __init__(self):
self.arm_bus = FeetechMotorsBus(
port="/dev/tty.usbmodem58760429571",
motors={
# "motor1": (2, "sts3250"),
# "motor2": (1, "scs0009"),
"shoulder_pitch": [1, "sts3250"],
"shoulder_yaw": [2, "sts3215"], # TODO: sts3250
"shoulder_roll": [3, "sts3215"], # TODO: sts3250
"elbow_flex": [4, "sts3250"],
"wrist_roll": [5, "sts3215"],
"wrist_yaw": [6, "sts3215"],
"wrist_pitch": [7, "sts3215"],
},
protocol_version=0,
)
self.hand_bus = FeetechMotorsBus(
port="/dev/tty.usbmodem585A0077581",
motors={
"thumb_basel_rotation": [30, "scs0009"],
"thumb_flexor": [27, "scs0009"],
"thumb_pinky_side": [26, "scs0009"],
"thumb_thumb_side": [28, "scs0009"],
"index_flexor": [25, "scs0009"],
"index_pinky_side": [31, "scs0009"],
"index_thumb_side": [32, "scs0009"],
"middle_flexor": [24, "scs0009"],
"middle_pinky_side": [33, "scs0009"],
"middle_thumb_side": [34, "scs0009"],
"ring_flexor": [21, "scs0009"],
"ring_pinky_side": [36, "scs0009"],
"ring_thumb_side": [35, "scs0009"],
"pinky_flexor": [23, "scs0009"],
"pinky_pinky_side": [38, "scs0009"],
"pinky_thumb_side": [37, "scs0009"],
},
protocol_version=1,
group_sync_read=False,
)
def get_hand_calibration(self):
homing_offset = [0] * len(self.hand_bus.motor_names)
drive_mode = [0] * len(self.hand_bus.motor_names)
start_pos = [
500,
900,
1000,
0,
100,
250,
750,
100,
400,
150,
100,
120,
980,
100,
950,
750,
]
end_pos = [
500 - 250,
900 - 300,
1000 - 550,
0 + 550,
1000,
start_pos[5] + 500,
start_pos[6] - 500,
1000,
400 + 700,
150 + 700,
1000,
120 + 700,
980 - 700,
1000,
950 - 700,
750 - 700,
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.hand_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.hand_bus.motor_names,
}
return calib_dict
def connect(self):
self.arm_bus.connect()
self.hand_bus.connect()
ESCAPE_KEY_ID = 27
def capture_and_display_processed_frames(
frame_processor: Callable[[np.ndarray], np.ndarray],
window_display_name: str,
cap_device: int = 0,
) -> None:
"""
Capture frames from the given input camera device, run them through
the frame processor, and display the outputs in a window with the given name.
User should press Esc to exit.
Inputs:
frame_processor: Callable[[np.ndarray], np.ndarray]
Processes frames.
Input and output are numpy arrays of shape (H W C) with BGR channel layout and dtype uint8 / byte.
window_display_name: str
Name of the window used to display frames.
cap_device: int
Identifier for the camera to use to capture frames.
"""
cv2.namedWindow(window_display_name)
capture = cv2.VideoCapture(cap_device)
if not capture.isOpened():
raise ValueError("Unable to open video capture.")
frame_count = 0
has_frame, frame = capture.read()
while has_frame:
assert isinstance(frame, np.ndarray)
frame_count = frame_count + 1
# mirror frame
frame = np.ascontiguousarray(frame[:, ::-1, ::-1])
# process & show frame
processed_frame = frame_processor(frame)
cv2.imshow(window_display_name, processed_frame[:, :, ::-1])
has_frame, frame = capture.read()
key = cv2.waitKey(1)
if key == ESCAPE_KEY_ID:
break
capture.release()
def main():
robot = HopeJuniorRobot()
robot.connect()
# robot.hand_bus.calibration = None
# breakpoint()
# print(robot.arm_bus.read("Present_Position"))
robot.arm_bus.write("Torque_Enable", 1)
robot.arm_bus.write("Acceleration", 20)
robot.arm_bus.read("Acceleration")
calibration = robot.get_hand_calibration()
robot.hand_bus.write("Goal_Position", calibration["start_pos"])
# robot.hand_bus.write("Goal_Position", calibration["end_pos"][:4], robot.hand_bus.motor_names[:4])
robot.hand_bus.set_calibration(calibration)
lol = 1
# # print(motors_bus.write("Goal_Position", 500))
# print(robot.hand_bus.read("Present_Position"))
# # pos = hand_bus.read("Present_Position")
# # hand_bus.write("Goal_Position", pos[0]+20, hand_bus.motor_names[0])
# # hand_bus.write("Goal_Position", pos[i]+delta, hand_bus.motor_names[i])
# robot.hand_bus.read("Acceleration")
# robot.hand_bus.write("Acceleration", 10)
# sleep = 1
# # robot.hand_bus.write(
# # "Goal_Position", [glove.last_d['index_2']-1500,300,300], ["index_pinky_side", "index_flexor", "index_thumb_side"]
# # )
# #time.sleep(sleep)
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [100, 100, 100], ["index_flexor", "index_pinky_side", "index_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [100, 0, 0], ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [200, 200, 0], ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
# )
# time.sleep(sleep)
# robot.hand_bus.write(
# "Goal_Position", [200, 100, 600], ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
# )
# time.sleep(sleep)
# breakpoint()
glove = HomonculusGlove()
glove.run_calibration()
# while True:
# joint_names = ["index_1", "index_2"]
# joint_values = glove.read(joint_names)
# print(joint_values)
input()
while True:
joint_names = []
# joint_names += ["thumb_0", "thumb_2", "thumb_3"]
joint_names += ["index_0", "index_1"]
# joint_names += ["middle_1", "middle_2"]
# joint_names += ["ring_1", "ring_2"]
# joint_names += ["pinky_0", "pinky_2"]
joint_values = glove.read(joint_names)
joint_values = joint_values.round().astype(int)
joint_dict = {k: v for k, v in zip(joint_names, joint_values, strict=False)}
motor_values = []
motor_names = []
# motor_names += ["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"]
# motor_values += [joint_dict["thumb_3"], joint_dict["thumb_0"], joint_dict["thumb_2"], joint_dict["thumb_2"]]
motor_names += ["index_pinky_side", "index_thumb_side"]
# if joint_dict["index_0"] -2100 > 0:
splayamount = 0.5
motor_values += [
(100 - joint_dict["index_0"]) * splayamount + joint_dict["index_1"] * (1 - splayamount),
(joint_dict["index_0"]) * splayamount + joint_dict["index_1"] * (1 - splayamount),
]
# else:
# motor_values += [100-joint_dict["index_0"], joint_dict["index_0"]]
# motor_names += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
# motor_values += [joint_dict["middle_2"], joint_dict["middle_1"], joint_dict["middle_1"]]
# motor_names += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
# motor_values += [joint_dict["ring_2"], joint_dict["ring_1"], joint_dict["ring_1"]]
# motor_names += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
# motor_values += [joint_dict["pinky_2"], joint_dict["pinky_0"], joint_dict["pinky_0"]]
motor_values = np.array(motor_values)
motor_values = np.clip(motor_values, 0, 100)
robot.hand_bus.write("Goal_Position", motor_values, motor_names)
time.sleep(0.02)
while True:
# print(glove.read()['index_2']-1500)
glove_index_flexor = glove.read()["index_2"] - 1500
glove_index_subflexor = glove.read()["index_1"] - 1500
glove_index_side = glove.read()["index_0"] - 2100
vals = [glove_index_flexor, 1000 - (glove_index_subflexor), glove_index_subflexor]
keys = ["index_flexor", "index_pinky_side", "index_thumb_side"]
glove_middle_flexor = glove.read()["middle_2"] - 1500
glove_middle_subflexor = 1000 - (glove.read()["middle_1"] - 1700)
vals += [glove_middle_flexor, glove_middle_subflexor, glove_middle_subflexor - 200]
keys += ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
glove_ring_flexor = glove.read()["ring_2"] - 1300
print(glove_ring_flexor)
glove_ring_subflexor = glove.read()["ring_1"] - 1100
vals += [glove_ring_flexor, 1000 - glove_ring_subflexor, glove_ring_subflexor]
keys += ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
glove_pinky_flexor = glove.read()["pinky_2"] - 1500
glove_pinky_subflexor = glove.read()["pinky_1"] - 1300
vals += [300 + glove_pinky_flexor, max(1000 - glove_pinky_subflexor - 100, 0), glove_pinky_subflexor]
keys += ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
robot.hand_bus.write("Goal_Position", vals, keys)
time.sleep(0.1)
time.sleep(3)
def move_arm(loop=10):
sleep = 1
for i in range(loop):
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1195])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 2195])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1457, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 2357, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 974, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 2674, 1957, 1695])
time.sleep(sleep + 2)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 1632, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 1369, 1632, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 1330, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [2381, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1681, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
robot.arm_bus.write("Goal_Position", [1981, 2030, 2069, 2032, 1874, 1957, 1695])
time.sleep(sleep)
def move_hand(loop=10):
sleep = 0.5
for i in range(loop):
robot.hand_bus.write(
"Goal_Position",
[500, 1000, 0, 1000],
["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [100, 100, 100], ["index_flexor", "index_pinky_side", "index_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [100, 1000, 150], ["middle_flexor", "middle_pinky_side", "middle_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [200, 200, 0], ["ring_flexor", "ring_pinky_side", "ring_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position", [200, 100, 700], ["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"]
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[500, 1000 - 250, 0 + 300, 1000 - 200],
["thumb_basel_rotation", "thumb_flexor", "thumb_pinky_side", "thumb_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[100 + 450, 100 + 400, 100 + 400],
["index_flexor", "index_pinky_side", "index_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[100 + 350, 1000 - 450, 150 + 450],
["middle_flexor", "middle_pinky_side", "middle_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[200 + 650, 200 + 350, 0 + 350],
["ring_flexor", "ring_pinky_side", "ring_thumb_side"],
)
time.sleep(sleep)
robot.hand_bus.write(
"Goal_Position",
[200 + 450, 100 + 400, 700 - 400],
["pinky_flexor", "pinky_pinky_side", "pinky_thumb_side"],
)
time.sleep(sleep)
move_hand(3)
move_arm(1)
from concurrent.futures import ThreadPoolExecutor
with ThreadPoolExecutor() as executor:
executor.submit(move_arm)
executor.submit(move_hand)
# initial position
for i in range(3):
robot.hand_bus.write(
"Goal_Position", [500, 1000, 0, 1000, 100, 950, 100, 100, 1000, 150, 200, 200, 0, 200, 100, 700]
)
time.sleep(1)
# for i in range(3):
# robot.hand_bus.write("Goal_Position", [500, 1000-150, 0+250, 1000-150,
# 100+300, 950-250, 100+250,
# 100+200, 1000-300, 150+300,
# 200+500, 200+200, 0+200,
# 200+300, 100+200, 700-200])
# time.sleep(1)
# camera = 0
# score_threshold = 0.95
# iou_threshold = 0.3
# app = MediaPipeHandApp(MediaPipeHand.from_pretrained(), score_threshold, iou_threshold)
# def frame_processor(frame: np.ndarray) -> np.ndarray:
# # Input Prep
# NHWC_int_numpy_frames, NCHW_fp32_torch_frames = app_to_net_image_inputs(frame)
# # Run Bounding Box & Keypoint Detector
# batched_selected_boxes, batched_selected_keypoints = app._run_box_detector(NCHW_fp32_torch_frames)
# # The region of interest ( bounding box of 4 (x, y) corners).
# # list[torch.Tensor(shape=[Num Boxes, 4, 2])],
# # where 2 == (x, y)
# #
# # A list element will be None if there is no selected ROI.
# batched_roi_4corners = app._compute_object_roi(batched_selected_boxes, batched_selected_keypoints)
# # selected landmarks for the ROI (if any)
# # list[torch.Tensor(shape=[Num Selected Landmarks, K, 3])],
# # where K == number of landmark keypoints, 3 == (x, y, confidence)
# #
# # A list element will be None if there is no ROI.
# landmarks_out = app._run_landmark_detector(NHWC_int_numpy_frames, batched_roi_4corners)
# app._draw_predictions(
# NHWC_int_numpy_frames,
# batched_selected_boxes,
# batched_selected_keypoints,
# batched_roi_4corners,
# *landmarks_out,
# )
# return NHWC_int_numpy_frames[0]
# capture_and_display_processed_frames(frame_processor, "QAIHM Mediapipe Hand Demo", camera)
if __name__ == "__main__":
main()

View File

@@ -0,0 +1,97 @@
#faulty servo
Model = [777]
ID = [7]
Baud_Rate = [0]
Return_Delay = [0]
Response_Status_Level = [1]
Min_Angle_Limit = [1140]
Max_Angle_Limit = [2750]
Max_Temperature_Limit = [70]
Max_Voltage_Limit = [140]
Min_Voltage_Limit = [40]
Max_Torque_Limit = [1000]
Phase = [12]
Unloading_Condition = [44]
LED_Alarm_Condition = [47]
P_Coefficient = [32]
D_Coefficient = [32]
I_Coefficient = [0]
Minimum_Startup_Force = [16]
CW_Dead_Zone = [1]
CCW_Dead_Zone = [1]
Protection_Current = [310]
Angular_Resolution = [1]
Offset = [1047]
Mode = [0]
Protective_Torque = [20]
Protection_Time = [200]
Overload_Torque = [80]
Speed_closed_loop_P_proportional_coefficient = [10]
Over_Current_Protection_Time = [200]
Velocity_closed_loop_I_integral_coefficient = [200]
Torque_Enable = [1]
Acceleration = [20]
Goal_Position = [0]
Goal_Time = [0]
Goal_Speed = [0]
Torque_Limit = [1000]
Lock = [1]
Present_Position = [1494]
Present_Speed = [0]
Present_Load = [0]
Present_Voltage = [123]
Present_Temperature = [24]
Status = [0]
Moving = [0]
Present_Current = [0]
Maximum_Acceleration = [306]
#all servos of hopejr
Model = [2825 777 777 2825 777 777 777]
ID = [1 2 3 4 5 6 7]
Baud_Rate = [0 0 0 0 0 0 0]
Return_Delay = [0 0 0 0 0 0 0]
Response_Status_Level = [1 1 1 1 1 1 1]
Min_Angle_Limit = [ 650 1300 1300 1200 600 1725 0]
Max_Angle_Limit = [2600 2050 2800 2500 4096 2250 4095]
Max_Temperature_Limit = [80 70 70 80 70 70 70]
Max_Voltage_Limit = [160 140 140 160 140 140 80]
Min_Voltage_Limit = [60 40 40 60 40 40 40]
Max_Torque_Limit = [1000 1000 1000 1000 1000 1000 1000]
Phase = [12 12 12 12 12 12 12]
Unloading_Condition = [45 44 44 45 44 44 44]
LED_Alarm_Condition = [45 47 47 45 47 47 47]
P_Coefficient = [32 32 32 32 32 32 32]
D_Coefficient = [32 32 32 32 32 32 32]
I_Coefficient = [0 0 0 0 0 0 0]
Minimum_Startup_Force = [15 16 16 12 16 16 16]
CW_Dead_Zone = [0 1 1 0 1 1 1]
CCW_Dead_Zone = [0 1 1 0 1 1 1]
Protection_Current = [310 310 310 310 310 310 500]
Angular_Resolution = [1 1 1 1 1 1 1]
Offset = [ 0 1047 1024 1047 1024 1024 0]
Mode = [0 0 0 0 0 0 0]
Protective_Torque = [20 20 20 20 20 20 20]
Protection_Time = [200 200 200 200 200 200 200]
Overload_Torque = [80 80 80 80 80 80 80]
Speed_closed_loop_P_proportional_coefficient = [10 10 10 10 10 10 10]
Over_Current_Protection_Time = [250 200 200 250 200 200 200]
Velocity_closed_loop_I_integral_coefficient = [200 200 200 200 200 200 200]
Torque_Enable = [1 1 1 1 1 1 1]
Acceleration = [20 20 20 20 20 20 20]
Goal_Position = [1909 1977 1820 1000 707 1941 1036]
Goal_Time = [0 0 0 0 0 0 0]
Goal_Speed = [0 0 0 0 0 0 0]
Torque_Limit = [1000 1000 1000 200 1000 1000 1000]
Lock = [1 1 1 1 1 1 1]
Present_Position = [1909 1982 1821 1200 710 1941 1036]
Present_Speed = [0 0 0 0 0 0 0]
Present_Load = [ 0 48 0 0 32 0 0]
Present_Voltage = [122 123 122 123 122 122 122]
Present_Temperature = [23 28 28 26 29 28 28]
Status = [0 0 0 0 0 0 1]
Moving = [0 0 0 0 0 0 0]
Present_Current = [0 1 0 1 1 0 1]
Maximum_Acceleration = [1530 306 306 1530 306 306 254]

View File

@@ -0,0 +1,192 @@
import threading
import time
from typing import Callable
import cv2
import numpy as np
import serial
from lerobot.common.robot_devices.motors.feetech import (
CalibrationMode,
FeetechMotorsBus,
)
LOWER_BOUND_LINEAR = -100
UPPER_BOUND_LINEAR = 200
ESCAPE_KEY_ID = 27
class HopeJuniorRobot:
def __init__(self):
self.arm_bus = FeetechMotorsBus(
port="/dev/ttyACM1",
motors={
# "motor1": (2, "sts3250"),
# "motor2": (1, "scs0009"),
#"shoulder_pitch": [1, "sts3250"],
#"shoulder_yaw": [2, "sts3215"], # TODO: sts3250
#"shoulder_roll": [3, "sts3215"], # TODO: sts3250
#"elbow_flex": [4, "sts3250"],
#"wrist_roll": [5, "sts3215"],
#"wrist_yaw": [6, "sts3215"],
"wrist_pitch": [7, "sts3215"],
},
protocol_version=0,
)
self.hand_bus = FeetechMotorsBus(
port="/dev/ttyACM1",
motors={
"thumb_basel_rotation": [30, "scs0009"],
"thumb_flexor": [27, "scs0009"],
"thumb_pinky_side": [26, "scs0009"],
"thumb_thumb_side": [28, "scs0009"],
"index_flexor": [25, "scs0009"],
"index_pinky_side": [31, "scs0009"],
"index_thumb_side": [32, "scs0009"],
"middle_flexor": [24, "scs0009"],
"middle_pinky_side": [33, "scs0009"],
"middle_thumb_side": [34, "scs0009"],
"ring_flexor": [21, "scs0009"],
"ring_pinky_side": [36, "scs0009"],
"ring_thumb_side": [35, "scs0009"],
"pinky_flexor": [23, "scs0009"],
"pinky_pinky_side": [38, "scs0009"],
"pinky_thumb_side": [37, "scs0009"],
},
protocol_version=1,
group_sync_read=False,
)
def get_hand_calibration(self):
"""
Returns a dictionary containing calibration settings for each motor
on the hand bus.
"""
homing_offset = [0] * len(self.hand_bus.motor_names)
drive_mode = [0] * len(self.hand_bus.motor_names)
start_pos = [
500, 900, 0, 1000, 100, 250, 750, 100, 400, 150, 100, 120, 980, 100, 950, 750,
]
end_pos = [
start_pos[0] - 400, # 500 - 400 = 100
start_pos[1] - 300, # 900 - 300 = 600
start_pos[2] + 550, # 0 + 550 = 550
start_pos[3] - 550, # 1000 - 550 = 450
start_pos[4] + 900, # 100 + 900 = 1000
start_pos[5] + 500, # 250 + 500 = 750
start_pos[6] - 500, # 750 - 500 = 250
start_pos[7] + 900, # 100 + 900 = 1000
start_pos[8] + 700, # 400 + 700 = 1100
start_pos[9] + 700, # 150 + 700 = 850
start_pos[10] + 900, # 100 + 900 = 1000
start_pos[11] + 700, # 120 + 700 = 820
start_pos[12] - 700, # 980 - 700 = 280
start_pos[13] + 900, # 100 + 900 = 1000
start_pos[14] - 700, # 950 - 700 = 250
start_pos[15] - 700, # 750 - 700 = 50
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.hand_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.hand_bus.motor_names,
}
return calib_dict
def get_arm_calibration(self):
"""
Returns a dictionary containing calibration settings for each motor
on the arm bus.
"""
homing_offset = [0] * len(self.arm_bus.motor_names)
drive_mode = [0] * len(self.arm_bus.motor_names)
# Example placeholders
start_pos = [
600, # shoulder_up
1500, # shoulder_forward
1300, # shoulder_yaw
1000, # bend_elbow
1600, # wrist_roll
1700, # wrist_yaw
600, # wrist_pitch
]
end_pos = [
2300, # shoulder_up
2300, # shoulder_forward
2800, # shoulder_yaw
2500, # bend_elbow
2800, # wrist_roll
2200, # wrist_yaw
1700, # wrist_pitch
]
calib_modes = [CalibrationMode.LINEAR.name] * len(self.arm_bus.motor_names)
calib_dict = {
"homing_offset": homing_offset,
"drive_mode": drive_mode,
"start_pos": start_pos,
"end_pos": end_pos,
"calib_mode": calib_modes,
"motor_names": self.arm_bus.motor_names,
}
return calib_dict
def connect(self):
"""Connect to the Feetech buses."""
self.arm_bus.connect()
# self.hand_bus.connect()
def capture_and_display_processed_frames(
frame_processor: Callable[[np.ndarray], np.ndarray],
window_display_name: str,
cap_device: int = 0,
) -> None:
"""
Capture frames from the given input camera device, run them through
the frame processor, and display the outputs in a window with the given name.
User should press Esc to exit.
Inputs:
frame_processor: Callable[[np.ndarray], np.ndarray]
Processes frames.
Input and output are numpy arrays of shape (H W C) with BGR channel layout and dtype uint8 / byte.
window_display_name: str
Name of the window used to display frames.
cap_device: int
Identifier for the camera to use to capture frames.
"""
cv2.namedWindow(window_display_name)
capture = cv2.VideoCapture(cap_device)
if not capture.isOpened():
raise ValueError("Unable to open video capture.")
frame_count = 0
has_frame, frame = capture.read()
while has_frame:
frame_count = frame_count + 1
# Mirror frame horizontally and flip color for demonstration
frame = np.ascontiguousarray(frame[:, ::-1, ::-1])
# process & show frame
processed_frame = frame_processor(frame)
cv2.imshow(window_display_name, processed_frame[:, :, ::-1])
has_frame, frame = capture.read()
key = cv2.waitKey(1)
if key == ESCAPE_KEY_ID:
break
capture.release()

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

View File

@@ -0,0 +1,44 @@
import matplotlib.pyplot as plt
import time
from typing import List, Tuple
def log_and_plot_params(bus, params_to_log: list, servo_names: list,
test_id="servo_log", interval=0.1, duration=5, save_plot=True) -> Tuple[dict, List[float]]:
"""
Logs specific servo parameters for a given duration and generates a plot.
"""
servo_data = {servo_name: {param: [] for param in params_to_log} for servo_name in servo_names}
timestamps = []
start_time = time.time()
while time.time() - start_time < duration:
timestamp = time.time() - start_time
timestamps.append(timestamp)
for param in params_to_log:
values = bus.read(param, servo_names)
for servo_name, value in zip(servo_names, values):
servo_data[servo_name][param].append(value)
time.sleep(interval)
if save_plot:
for servo_name, data in servo_data.items():
plt.figure(figsize=(10, 6))
for param in params_to_log:
if all(v is not None for v in data[param]):
plt.plot(timestamps, data[param], label=param)
plt.xlabel("Time (s)")
plt.ylabel("Parameter Values")
plt.title(f"Parameter Trends for Servo: {servo_name}")
plt.legend()
plt.grid(True)
plt.tight_layout()
plot_filename = f"{test_id}_{servo_name}.png"
plt.savefig(plot_filename)
print(f"Plot saved as {plot_filename}")
return servo_data, timestamps

Binary file not shown.

After

Width:  |  Height:  |  Size: 65 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 60 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

View File

@@ -0,0 +1,68 @@
STS_SERIES_CONTROL_TABLE = {
"Model": (3, 2),
"ID": (5, 1),
"Baud_Rate": (6, 1),
"Return_Delay": (7, 1),
"Response_Status_Level": (8, 1),
"Min_Angle_Limit": (9, 2),
"Max_Angle_Limit": (11, 2),
"Max_Temperature_Limit": (13, 1),
"Max_Voltage_Limit": (14, 1),
"Min_Voltage_Limit": (15, 1),
"Max_Torque_Limit": (16, 2),
"Phase": (18, 1),
"Unloading_Condition": (19, 1),
"LED_Alarm_Condition": (20, 1),
"P_Coefficient": (21, 1),
"D_Coefficient": (22, 1),
"I_Coefficient": (23, 1),
"Minimum_Startup_Force": (24, 2),
"CW_Dead_Zone": (26, 1),
"CCW_Dead_Zone": (27, 1),
"Protection_Current": (28, 2),
"Angular_Resolution": (30, 1),
"Offset": (31, 2),
"Mode": (33, 1),
"Protective_Torque": (34, 1),
"Protection_Time": (35, 1),
"Overload_Torque": (36, 1),
"Speed_closed_loop_P_proportional_coefficient": (37, 1),
"Over_Current_Protection_Time": (38, 1),
"Velocity_closed_loop_I_integral_coefficient": (39, 1),
"Torque_Enable": (40, 1),
"Acceleration": (41, 1),
"Goal_Position": (42, 2),
"Goal_Time": (44, 2),
"Goal_Speed": (46, 2),
"Torque_Limit": (48, 2),
"Lock": (55, 1),
"Present_Position": (56, 2),
"Present_Speed": (58, 2),
"Present_Load": (60, 2),
"Present_Voltage": (62, 1),
"Present_Temperature": (63, 1),
"Status": (65, 1),
"Moving": (66, 1),
"Present_Current": (69, 2),
# Not in the Memory Table
"Maximum_Acceleration": (85, 2),
}
import time
# Assuming STS_SERIES_CONTROL_TABLE is defined globally
def print_all_params(robot):
"""
Reads all parameters from the STS_SERIES_CONTROL_TABLE and prints their values.
"""
for param in STS_SERIES_CONTROL_TABLE.keys():
try:
val = robot.arm_bus.read(param)
print(f"{param} = {val}")
except Exception as e:
print(f"{param} read failed: {e}")
# Example usage:
print_all_params(robot)

View File

@@ -0,0 +1,26 @@
#include <DFRobot_VisualRotaryEncoder.h>
DFRobot_VisualRotaryEncoder_I2C sensor(0x54, &Wire);
void setup()
{
Serial.begin(115200);
// Attempt to initialize the sensor
while (NO_ERR != sensor.begin()) {
// Failed? Just wait a bit and try again
delay(3000);
}
}
void loop()
{
// Read the encoder value
uint16_t encoderValue = sensor.getEncoderValue();
// Print it followed by a newline
Serial.println(encoderValue);
// Delay 10ms between readings
delay(10);
}

View File

@@ -0,0 +1,544 @@
{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"what are the actual interest values on the hopejr? make like a map"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"can change these dynamically so if the arm is moving down we can relax it instead of tensing it? so for example decreasing torque if the target position is lower than the actual position, for example. "
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"arm_calibration = robot.get_arm_calibration()\n",
"robot.arm_bus.write(\"Goal_Position\", arm_calibration[\"start_pos\"])"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Present Position: [1494]\n",
"Acceleration Read: [20]\n"
]
}
],
"source": [
"import time\n",
"from hopejr import HopeJuniorRobot\n",
"\n",
"\n",
"robot = HopeJuniorRobot()\n",
"robot.connect()\n",
"\n",
"# Example read of the current position\n",
"print(\"Present Position:\", robot.arm_bus.read(\"Present_Position\"))\n",
"\n",
"# Enable torque and set acceleration\n",
"robot.arm_bus.write(\"Torque_Enable\", 1)\n",
"robot.arm_bus.write(\"Acceleration\", 20)\n",
"print(\"Acceleration Read:\", robot.arm_bus.read(\"Acceleration\"))\n"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"Torque_Limit\", 100,[\"elbow_flex\"])\n",
"robot.arm_bus.write(\"Protective_Torque\", 0, [\"elbow_flex\"])\n",
"robot.arm_bus.write(\"Acceleration\", 20)\n",
"robot.arm_bus.write(\"Goal_Position\", [2000], [\"elbow_flex\"])"
]
},
{
"cell_type": "code",
"execution_count": 8,
"metadata": {},
"outputs": [
{
"data": {
"text/plain": [
"array([1000, 1000, 1000, 1000, 1000, 1000, 1000])"
]
},
"execution_count": 8,
"metadata": {},
"output_type": "execute_result"
}
],
"source": [
"robot.arm_bus.read(\"Max_Torque_Limit\")"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"Goal_Position\", [1909, 1977, 1820, 1000, 707, 1941, 1036]) #"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"Max_Voltage_Limit\", [160, 140, 140, 160, 140, 140, 140]) #so its not torque limit nor max torque limit, , no protective torque or overload torque\n",
"#it's 1) max voltage limit, min-max angle limits are arbitrairly set for all the motors, max temp is only set for the shoulder\n",
"#max acceleration is also set, we could lower that in the elbow to make it less responsive to commands basically\n",
"#so we limit speed and temperature, maybe we should limit torque thouhg, minimum startup force is also important. protection current as well\n",
"#changed that to 310.\n",
"#\"Max_Voltage_Limit\" also needs to be changed, different from torque_limit"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Model = [777]\n",
"ID = [7]\n",
"Baud_Rate = [0]\n",
"Return_Delay = [0]\n",
"Response_Status_Level = [1]\n",
"Min_Angle_Limit = [1140]\n",
"Max_Angle_Limit = [2750]\n",
"Max_Temperature_Limit = [70]\n",
"Max_Voltage_Limit = [140]\n",
"Min_Voltage_Limit = [40]\n",
"Max_Torque_Limit = [1000]\n",
"Phase = [12]\n",
"Unloading_Condition = [44]\n",
"LED_Alarm_Condition = [47]\n",
"P_Coefficient = [32]\n",
"D_Coefficient = [32]\n",
"I_Coefficient = [0]\n",
"Minimum_Startup_Force = [16]\n",
"CW_Dead_Zone = [1]\n",
"CCW_Dead_Zone = [1]\n",
"Protection_Current = [310]\n",
"Angular_Resolution = [1]\n",
"Offset = [1047]\n",
"Mode = [0]\n",
"Protective_Torque = [20]\n",
"Protection_Time = [200]\n",
"Overload_Torque = [80]\n",
"Speed_closed_loop_P_proportional_coefficient = [10]\n",
"Over_Current_Protection_Time = [200]\n",
"Velocity_closed_loop_I_integral_coefficient = [200]\n",
"Torque_Enable = [1]\n",
"Acceleration = [20]\n",
"Goal_Position = [0]\n",
"Goal_Time = [0]\n",
"Goal_Speed = [0]\n",
"Torque_Limit = [1000]\n",
"Lock = [1]\n",
"Present_Position = [1494]\n",
"Present_Speed = [0]\n",
"Present_Load = [0]\n",
"Present_Voltage = [123]\n",
"Present_Temperature = [24]\n",
"Status = [0]\n",
"Moving = [0]\n",
"Present_Current = [0]\n",
"Maximum_Acceleration = [306]\n"
]
}
],
"source": [
"STS_SERIES_CONTROL_TABLE = {\n",
" \"Model\": (3, 2),\n",
" \"ID\": (5, 1),\n",
" \"Baud_Rate\": (6, 1),\n",
" \"Return_Delay\": (7, 1),\n",
" \"Response_Status_Level\": (8, 1),\n",
" \"Min_Angle_Limit\": (9, 2),\n",
" \"Max_Angle_Limit\": (11, 2),\n",
" \"Max_Temperature_Limit\": (13, 1),\n",
" \"Max_Voltage_Limit\": (14, 1),\n",
" \"Min_Voltage_Limit\": (15, 1),\n",
" \"Max_Torque_Limit\": (16, 2),\n",
" \"Phase\": (18, 1),\n",
" \"Unloading_Condition\": (19, 1),\n",
" \"LED_Alarm_Condition\": (20, 1),\n",
" \"P_Coefficient\": (21, 1),\n",
" \"D_Coefficient\": (22, 1),\n",
" \"I_Coefficient\": (23, 1),\n",
" \"Minimum_Startup_Force\": (24, 2),\n",
" \"CW_Dead_Zone\": (26, 1),\n",
" \"CCW_Dead_Zone\": (27, 1),\n",
" \"Protection_Current\": (28, 2),\n",
" \"Angular_Resolution\": (30, 1),\n",
" \"Offset\": (31, 2),\n",
" \"Mode\": (33, 1),\n",
" \"Protective_Torque\": (34, 1),\n",
" \"Protection_Time\": (35, 1),\n",
" \"Overload_Torque\": (36, 1),\n",
" \"Speed_closed_loop_P_proportional_coefficient\": (37, 1),\n",
" \"Over_Current_Protection_Time\": (38, 1),\n",
" \"Velocity_closed_loop_I_integral_coefficient\": (39, 1),\n",
" \"Torque_Enable\": (40, 1),\n",
" \"Acceleration\": (41, 1),\n",
" \"Goal_Position\": (42, 2),\n",
" \"Goal_Time\": (44, 2),\n",
" \"Goal_Speed\": (46, 2),\n",
" \"Torque_Limit\": (48, 2),\n",
" \"Lock\": (55, 1),\n",
" \"Present_Position\": (56, 2),\n",
" \"Present_Speed\": (58, 2),\n",
" \"Present_Load\": (60, 2),\n",
" \"Present_Voltage\": (62, 1),\n",
" \"Present_Temperature\": (63, 1),\n",
" \"Status\": (65, 1),\n",
" \"Moving\": (66, 1),\n",
" \"Present_Current\": (69, 2),\n",
" # Not in the Memory Table\n",
" \"Maximum_Acceleration\": (85, 2),\n",
"}\n",
"\n",
"import time\n",
"\n",
"# Assuming STS_SERIES_CONTROL_TABLE is defined globally\n",
"\n",
"def print_all_params(robot):\n",
" \"\"\"\n",
" Reads all parameters from the STS_SERIES_CONTROL_TABLE and prints their values.\n",
" \"\"\"\n",
" for param in STS_SERIES_CONTROL_TABLE.keys():\n",
" try:\n",
" val = robot.arm_bus.read(param)\n",
" print(f\"{param} = {val}\")\n",
" except Exception as e:\n",
" print(f\"{param} read failed: {e}\")\n",
"\n",
"\n",
"# Example usage:\n",
"print_all_params(robot)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"probably max input voltage, we can also look at temperature and "
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Acceleration Read: [20 20]\n"
]
}
],
"source": [
"\n",
"print(\"Acceleration Read:\", robot.arm_bus.read(\"Acceleration\"))"
]
},
{
"cell_type": "code",
"execution_count": 37,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"LED_Alarm_Condition\", 2, [\"elbow_flex\"])"
]
},
{
"cell_type": "code",
"execution_count": 16,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"Acceleration\", 20, [\"elbow_flex\"])\n",
"robot.arm_bus.write(\"Acceleration\", 100, [\"wrist_yaw\"])"
]
},
{
"cell_type": "code",
"execution_count": 73,
"metadata": {},
"outputs": [],
"source": []
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"Goal_Position\", [1000, 1000], [\"elbow_flex\", \"wrist_yaw\"])\n",
"time.sleep(2)\n",
"robot.arm_bus.write(\"Goal_Position\", [2000, 2000], [\"elbow_flex\", \"wrist_yaw\"])"
]
},
{
"cell_type": "code",
"execution_count": 68,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [0]\n",
"Elbow Flex Current: [3]\n",
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [2]\n",
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [2]\n",
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [1]\n",
"Elbow Flex Current: [0]\n"
]
},
{
"ename": "KeyboardInterrupt",
"evalue": "",
"output_type": "error",
"traceback": [
"\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
"\u001b[0;31mKeyboardInterrupt\u001b[0m Traceback (most recent call last)",
"Cell \u001b[0;32mIn[68], line 25\u001b[0m\n\u001b[1;32m 22\u001b[0m time\u001b[38;5;241m.\u001b[39msleep(\u001b[38;5;241m2\u001b[39m)\n\u001b[1;32m 23\u001b[0m \u001b[38;5;28;01melse\u001b[39;00m:\n\u001b[1;32m 24\u001b[0m \u001b[38;5;66;03m# If current is zero, hold at pos_a for a bit\u001b[39;00m\n\u001b[0;32m---> 25\u001b[0m \u001b[43mtime\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43msleep\u001b[49m\u001b[43m(\u001b[49m\u001b[38;5;241;43m1\u001b[39;49m\u001b[43m)\u001b[49m\n",
"\u001b[0;31mKeyboardInterrupt\u001b[0m: "
]
}
],
"source": [
"import time\n",
"\n",
"# Enable torque on elbow_flex\n",
"robot.arm_bus.write(\"Torque_Enable\", 1, [\"elbow_flex\"])\n",
"\n",
"pos_a = 2500\n",
"pos_b = 1000\n",
"\n",
"robot.arm_bus.write(\"Goal_Position\", pos_a, [\"elbow_flex\"])\n",
"time.sleep(2)\n",
"\n",
"while True:\n",
" current_val = robot.arm_bus.read(\"Present_Current\", \"elbow_flex\")\n",
" print(\"Elbow Flex Current:\", current_val)\n",
" \n",
" # If the servo is under non-zero load/current, switch position\n",
" if current_val > 1:\n",
" robot.arm_bus.write(\"Goal_Position\", pos_b, [\"elbow_flex\"])\n",
" time.sleep(2)\n",
" # Go back to pos_a again\n",
" robot.arm_bus.write(\"Goal_Position\", pos_a, [\"elbow_flex\"])\n",
" time.sleep(2)\n",
" else:\n",
" # If current is zero, hold at pos_a for a bit\n",
" time.sleep(1)\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"\"Acceleration\" = 0, infinitely fast\n",
"\"Acceleration\" = 20 slow\n",
"elbow_flex is the LED one (4)\n",
"\n",
"robot.arm_bus.write(\"LED_Alarm_Condition\", 2, [\"elbow_flex\"]) #on constantly\n",
"robot.arm_bus.write(\"LED_Alarm_Condition\", 1, [\"elbow_flex\"]) #beeping\n",
"robot.arm_bus.write(\"LED_Alarm_Condition\", 0, [\"elbow_flex\"]) #off\n",
"\n",
"\"Max_Torque_Limit\": (16, 2), is what i have o play around with or \"Protective_Torque\": (37, 1), maybe\n",
"\n",
"robot.arm_bus.write(\"Torque_Enable\", 1, [\"elbow_flex\"]) 1 can move 0 cant move\n",
"\n",
"robot.arm_bus.write(\"Torque_Limit\", 300, [\"elbow_flex\"]) #how strong/weak the servo is. 0 makes it so that it cannot move basically, but i'd like to have that value change honestly and for it to be waeaker\n",
"\n",
"robot.arm_bus.write(\"Torque_Limit\", 20,[\"elbow_flex\"]) 20 in ordre to get some motion\n",
"\n",
"default is 1000\n",
"\n",
"robot.arm_bus.write(\"Goal_Speed\", -s, [\"elbow_flex\"]) #changes how fast the servo moves when going to the target, does not make it move with a specific speed "
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"import time\n",
"\n",
"# Enable torque on elbow_flex\n",
"robot.arm_bus.write(\"Torque_Enable\", 1, [\"elbow_flex\"])\n",
"\n",
"pos_a = 1000\n",
"pos_b = 2500\n",
"\n",
"robot.arm_bus.write(\"Goal_Position\", pos_a, [\"elbow_flex\"])\n",
"time.sleep(2)\n",
"\n",
"while True:\n",
" current_val = robot.arm_bus.read(\"Present_Current\", \"elbow_flex\")\n",
" print(\"Elbow Flex Current:\", current_val)\n",
" \n",
" # If the servo is under non-zero load/current, switch position\n",
" if current_val > 1:\n",
" robot.arm_bus.write(\"Goal_Position\", pos_b, [\"elbow_flex\"])\n",
" time.sleep(2)\n",
" # Go back to pos_a again\n",
" robot.arm_bus.write(\"Goal_Position\", pos_a, [\"elbow_flex\"])\n",
" time.sleep(2)\n",
" else:\n",
" # If current is zero, hold at pos_a for a bit\n",
" time.sleep(1)\n",
"\n",
"\n",
"so if current is larger than x then you disable it \n",
"\n"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"robot.arm_bus.write(\"LED_Alarm_Condition\", 2, [\"elbow_flex\"])"
]
},
{
"cell_type": "code",
"execution_count": 43,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"[0]\n",
"[0]\n",
"[2]\n",
"[4]\n",
"[0]\n",
"[0]\n",
"[0]\n"
]
},
{
"ename": "KeyboardInterrupt",
"evalue": "",
"output_type": "error",
"traceback": [
"\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
"\u001b[0;31mKeyboardInterrupt\u001b[0m Traceback (most recent call last)",
"Cell \u001b[0;32mIn[43], line 3\u001b[0m\n\u001b[1;32m 1\u001b[0m \u001b[38;5;28;01mwhile\u001b[39;00m \u001b[38;5;28;01mTrue\u001b[39;00m:\n\u001b[1;32m 2\u001b[0m \u001b[38;5;28mprint\u001b[39m(robot\u001b[38;5;241m.\u001b[39marm_bus\u001b[38;5;241m.\u001b[39mread(\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mPresent_Current\u001b[39m\u001b[38;5;124m\"\u001b[39m, [\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124melbow_flex\u001b[39m\u001b[38;5;124m\"\u001b[39m]))\n\u001b[0;32m----> 3\u001b[0m \u001b[43mtime\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43msleep\u001b[49m\u001b[43m(\u001b[49m\u001b[38;5;241;43m1\u001b[39;49m\u001b[43m)\u001b[49m\n",
"\u001b[0;31mKeyboardInterrupt\u001b[0m: "
]
}
],
"source": [
"while True:\n",
" print(robot.arm_bus.read(\"Present_Current\", [\"elbow_flex\"]))\n",
" time.sleep(1)"
]
},
{
"cell_type": "code",
"execution_count": 47,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"Max_Voltage_Limit = [160 140 140 160 140 140 80]\n",
"Min_Angle_Limit = [ 650 1300 1300 1200 600 1725 0]\n",
"Max_Angle_Limit = [2600 2050 2800 2500 4096 2250 4095]\n",
"Max_Temperature_Limit = [80 70 70 80 70 70 70]\n",
"Acceleration = [20 20 20 20 20 20 20]\n",
"Torque_Limit = [1000 1000 1000 200 1000 1000 1000]\n",
"Minimum_Startup_Force = [15 16 16 12 16 16 16]\n",
"Protection_Current = [310 310 310 310 310 310 500]\n"
]
}
],
"source": [
"import time\n",
"\n",
"def print_important_params(robot):\n",
"\n",
" # Example parameters you mentioned; adjust as needed\n",
" param_list = [\n",
" \"Max_Voltage_Limit\",\n",
" \"Min_Angle_Limit\",\n",
" \"Max_Angle_Limit\",\n",
" \"Max_Temperature_Limit\",\n",
" \"Acceleration\", # or \"Maximum_Acceleration\" if you prefer that register\n",
" \"Torque_Limit\", # or \"Max_Torque_Limit\" if your table uses that\n",
" \"Minimum_Startup_Force\",\n",
" \"Protection_Current\",\n",
" ]\n",
" \n",
" for param in param_list:\n",
" try:\n",
" val = robot.arm_bus.read(param)\n",
" print(f\"{param} = {val}\")\n",
" except Exception as e:\n",
" print(f\"{param} read failed: {e}\")\n",
"\n",
"# -------------------------------\n",
"# Example usage\n",
"\n",
"print_important_params(robot)\n"
]
}
],
"metadata": {
"kernelspec": {
"display_name": "lerobot",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.10.16"
}
},
"nbformat": 4,
"nbformat_minor": 2
}

View File

@@ -0,0 +1,27 @@
import time
from hopejr import HopeJuniorRobot
def main():
# Instantiate and connect to the robot
robot = HopeJuniorRobot()
robot.connect()
# Example read of the current position
print("Present Position:", robot.arm_bus.read("Present_Position"))
# Enable torque and set acceleration
robot.arm_bus.write("Torque_Enable", 1)
robot.arm_bus.write("Acceleration", 20)
print("Acceleration Read:", robot.arm_bus.read("Acceleration"))
# Move elbow_flex and wrist_yaw a few times
robot.arm_bus.write("Goal_Position", [1000, 1000], ["elbow_flex", "wrist_yaw"])
time.sleep(2)
robot.arm_bus.write("Goal_Position", [1500, 1500], ["elbow_flex", "wrist_yaw"])
time.sleep(2)
robot.arm_bus.write("Goal_Position", [1000, 1000], ["elbow_flex", "wrist_yaw"])
if __name__ == "__main__":
main()

View File

@@ -0,0 +1,49 @@
STS_SERIES_CONTROL_TABLE = {
"Model": (3, 2),
"ID": (5, 1),
"Baud_Rate": (6, 1),
"Return_Delay": (7, 1),
"Response_Status_Level": (8, 1),
"Min_Angle_Limit": (9, 2),
"Max_Angle_Limit": (11, 2),
"Max_Temperature_Limit": (13, 1),
"Max_Voltage_Limit": (14, 1),
"Min_Voltage_Limit": (15, 1),
"Max_Torque_Limit": (16, 2),
"Phase": (18, 1),
"Unloading_Condition": (19, 1),
"LED_Alarm_Condition": (20, 1),
"P_Coefficient": (21, 1),
"D_Coefficient": (22, 1),
"I_Coefficient": (23, 1),
"Minimum_Startup_Force": (24, 2),
"CW_Dead_Zone": (26, 1),
"CCW_Dead_Zone": (27, 1),
"Protection_Current": (28, 2),
"Angular_Resolution": (30, 1),
"Offset": (31, 2),
"Mode": (33, 1),
"Protective_Torque": (34, 1),
"Protection_Time": (35, 1),
"Overload_Torque": (36, 1),
"Speed_closed_loop_P_proportional_coefficient": (37, 1),
"Over_Current_Protection_Time": (38, 1),
"Velocity_closed_loop_I_integral_coefficient": (39, 1),
"Torque_Enable": (40, 1),
"Acceleration": (41, 1),
"Goal_Position": (42, 2),
"Goal_Time": (44, 2),
"Goal_Speed": (46, 2),
"Torque_Limit": (48, 2),
"Lock": (55, 1),
"Present_Position": (56, 2),
"Present_Speed": (58, 2),
"Present_Load": (60, 2),
"Present_Voltage": (62, 1),
"Present_Temperature": (63, 1),
"Status": (65, 1),
"Moving": (66, 1),
"Present_Current": (69, 2),
# Not in the Memory Table
"Maximum_Acceleration": (85, 2),
}

View File

@@ -0,0 +1,16 @@
First check that kicks in is current:
Protection_Current (310) amperes or sth
Present_Current, compared against protection crrent
Over_Current_Protection_Time, how long until you shut it down
make a quick update about this
variables of interest are
Max_Torque_Limit = 1000,
Present_Load = 1000-something, which triggered the overload torque mechanism
Overload_Torque = 80, how much of the max torque limit do we allow?
Protection_Time = 200, after how long do we set Torque_Enable to 1? *not true lol
Protective_Torque = 20, after we trigger the safety mechanism, how much torque do we allow the motor to have?
theres actually no temperature or voltage check that the feetechs perform, the only two are current and torque, which works like i said above

View File

@@ -106,6 +106,6 @@ def make_policy(
policy = policy_cls(policy_cfg)
policy.load_state_dict(policy_cls.from_pretrained(pretrained_policy_name_or_path).state_dict())
policy.to(get_safe_torch_device(hydra_cfg.device))
#policy.to(get_safe_torch_device(hydra_cfg.device))
return policy

View File

@@ -404,9 +404,7 @@ class OpenCVCamera:
h, w, _ = color_image.shape
if h != self.height or w != self.width:
raise OSError(
f"Can't capture color image with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead."
)
color_image = cv2.resize(color_image, (640, 480))
if self.rotation is not None:
color_image = cv2.rotate(color_image, self.rotation)

View File

@@ -41,7 +41,7 @@ def log_control_info(robot: Robot, dt_s, episode_index=None, frame_index=None, f
# total step time displayed in milliseconds and its frequency
log_dt("dt", dt_s)
return
# TODO(aliberts): move robot-specific logs logic in robot.print_logs()
if not robot.robot_type.startswith("stretch"):
for name in robot.leader_arms:
@@ -94,7 +94,7 @@ def predict_action(observation, policy, device, use_amp):
observation = copy(observation)
with (
torch.inference_mode(),
torch.autocast(device_type=device.type) if device.type == "cuda" and use_amp else nullcontext(),
torch.autocast(device_type=device),
):
# Convert to pytorch format: channel first and float32 in [0,1] with batch dimension
for name in observation:
@@ -165,7 +165,8 @@ def init_policy(pretrained_policy_name_or_path, policy_overrides):
policy = make_policy(hydra_cfg=hydra_cfg, pretrained_policy_name_or_path=pretrained_policy_path)
# Check device is available
device = get_safe_torch_device(hydra_cfg.device, log=True)
#device = get_safe_torch_device(hydra_cfg.device, log=True)
device="mps"
use_amp = hydra_cfg.use_amp
policy_fps = hydra_cfg.env.fps
@@ -254,7 +255,6 @@ def control_loop(
start_episode_t = time.perf_counter()
while timestamp < control_time_s:
start_loop_t = time.perf_counter()
if teleoperate:
observation, action = robot.teleop_step(record_data=True)
else:
@@ -281,7 +281,7 @@ def control_loop(
busy_wait(1 / fps - dt_s)
dt_s = time.perf_counter() - start_loop_t
log_control_info(robot, dt_s, fps=fps)
#log_control_info(robot, dt_s, fps=fps)
timestamp = time.perf_counter() - start_episode_t
if events["exit_early"]:

View File

@@ -37,7 +37,15 @@ HALF_TURN_DEGREE = 180
# See this link for STS3215 Memory Table:
# https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
# data_name: (address, size_byte)
SCS_SERIES_CONTROL_TABLE = {
#####SAFETY CHECKS EXPLAINED#####
#There are two safety checks built-in: one is based on load and the other is based on current.
#Current: if Protection_Current > Present_Current we wait Over_Current_Protection_Time (expressed in ms) and set Torque_Enable to 0
#Load: if Max_Torque_Limit*Overload_Torque (expressed as a percentage) > Present_Load, we wait Protection_Time (expressed in ms
#and set Max_Torque_Limit to Protective_Torque)
#Though we can specify Min-Max_Angle_Limit, Max_Temperature_Limit, Min-Max_Voltage_Limit, no safety checks are implemented for these values
STS_SERIES_CONTROL_TABLE = {
"Model": (3, 2),
"ID": (5, 1),
"Baud_Rate": (6, 1),
@@ -87,6 +95,124 @@ SCS_SERIES_CONTROL_TABLE = {
"Maximum_Acceleration": (85, 2),
}
SCS_SERIES_CONTROL_TABLE = {
"Model": (3, 2),
"ID": (5, 1),
"Baud_Rate": (6, 1),
"Return_Delay": (7, 1),
"Response_Status_Level": (8, 1),
"Min_Angle_Limit": (9, 2),
"Max_Angle_Limit": (11, 2),
"Max_Temperature_Limit": (13, 1),
"Max_Voltage_Limit": (14, 1),
"Min_Voltage_Limit": (15, 1),
"Max_Torque_Limit": (16, 2),
"Phase": (18, 1),
"Unloading_Condition": (19, 1),
"LED_Alarm_Condition": (20, 1),
"P_Coefficient": (21, 1),
"D_Coefficient": (22, 1),
"I_Coefficient": (23, 1),
"Minimum_Startup_Force": (24, 2),
"CW_Dead_Zone": (26, 1),
"CCW_Dead_Zone": (27, 1),
# "Protection_Current": (28, 2),
# "Angular_Resolution": (30, 1),
# "Offset": (31, 2),
# "Mode": (33, 1),
"Protective_Torque": (37, 1),
"Protection_Time": (38, 1),
"Torque_Enable": (40, 1),
"Acceleration": (41, 1),
"Goal_Position": (42, 2),
"Running_Time": (44, 2),
"Goal_Speed": (46, 2),
"Lock": (48, 1),
"Present_Position": (56, 2),
"Present_Speed": (58, 2),
"Present_Load": (60, 2),
"Present_Voltage": (62, 1),
"Present_Temperature": (63, 1),
"Sync_Write_Flag": (64, 1),
"Status": (65, 1),
"Moving": (66, 1),
# "Overload_Torque": (36, 1),
# "Speed_closed_loop_P_proportional_coefficient": (37, 1),
# "Over_Current_Protection_Time": (38, 1),
# "Velocity_closed_loop_I_integral_coefficient": (39, 1),
# "Acceleration": (41, 1),
# "Goal_Time": (44, 2),
# "Torque_Limit": (48, 2),
# "Present_Current": (69, 2),
# # Not in the Memory Table
# "Maximum_Acceleration": (85, 2),
}
SM_SERIES_CONTROL_TABLE = {
"Firmware_Main_Version_No": (0, 1),
"Firmware_Secondary_Version_No": (1, 1),
"Servo_Main_Version_No": (3, 1),
"Servo_Secondary_Version_No": (4, 1),
"ID": (5, 1),
"Baud_Rate": (6, 1),
"Return_Delay": (7, 1),
"Response_Status_Level": (8, 1),
"Min_Position_Limit": (9, 2),
"Max_Position_Limit": (11, 2),
"Max_Temperature_Limit": (13, 1),
"Max_Input_Voltage": (14, 1),
"Min_Input_Voltage": (15, 1),
"Max_Torque_Limit": (16, 2),
"Unloading_Condition": (19, 1),
"LED_Alarm_Condition": (20, 1),
"P_Coefficient_Location_Ring": (21, 1),
"D_Coefficient_Location_Ring": (22, 1),
"I_Coefficient_Location_Ring": (23, 1),
"Minimum_Startup_Force": (24, 2),
"CW_Dead_Zone": (26, 1),
"CCW_Dead_Zone": (27, 1),
"Protection_Current": (28, 2),
"Angular_Resolution": (30, 1),
"Offset": (31, 2),
"Drive_Mode": (33, 1),
"Protective_Torque": (34, 1),
"Protection_Time": (35, 1),
"Overload_Torque": (36, 1),
"Speed_closed_loop_P_proportional_coefficient": (37, 1),
"Over_Current_Protection_Time": (38, 1),
"Velocity_closed_loop_I_integral_coefficient": (39, 1),
"Torque_Enable": (40, 1),
"Acceleration": (41, 1),
"Goal_Position": (42, 2),
"Goal_Speed": (46, 2),
"Torque_Limit": (48, 2),
"Lock": (55, 1),
"Present_Position": (56, 2),
"Present_Speed": (58, 2),
"Present_Load": (60, 2),
"Present_Voltage": (62, 1),
"Present_Temperature": (63, 1),
"Status": (65, 1),
"Moving": (66, 1),
"Present_Current": (69, 2),
# Not in the Memory Table
"Maximum_Acceleration": (85, 2),
}
STS_SERIES_BAUDRATE_TABLE = {
0: 1_000_000,
1: 500_000,
2: 250_000,
3: 128_000,
4: 115_200,
5: 57_600,
6: 38_400,
7: 19_200,
}
SCS_SERIES_BAUDRATE_TABLE = {
0: 1_000_000,
1: 500_000,
@@ -98,27 +224,50 @@ SCS_SERIES_BAUDRATE_TABLE = {
7: 19_200,
}
SM_SERIES_BAUDRATE_TABLE = {
0: 1_000_000,
1: 500_000,
2: 250_000,
3: 128_000,
4: 115_200,#default
5: 76_800,
6: 57_600,
7: 38_400,
}
CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "sm8512blPresent_Position"]
MODEL_CONTROL_TABLE = {
"sts_series": STS_SERIES_CONTROL_TABLE,
"scs_series": SCS_SERIES_CONTROL_TABLE,
"sts3215": SCS_SERIES_CONTROL_TABLE,
"sts3215": STS_SERIES_CONTROL_TABLE,
"sts3250": STS_SERIES_CONTROL_TABLE,
"scs0009": SCS_SERIES_CONTROL_TABLE,
"sm8512bl": SM_SERIES_CONTROL_TABLE,
}
MODEL_RESOLUTION = {
"scs_series": 4096,
"sts_series": 4096,
"scs_series": 1024,
"sts3215": 4096,
"sts3250": 4096,
"scs0009": 1024,
"sm8512bl": 4096,
}
MODEL_BAUDRATE_TABLE = {
"sts_series": STS_SERIES_BAUDRATE_TABLE,
"scs_series": SCS_SERIES_BAUDRATE_TABLE,
"sts3215": SCS_SERIES_BAUDRATE_TABLE,
"sts3215": STS_SERIES_BAUDRATE_TABLE,
"sts3250": STS_SERIES_BAUDRATE_TABLE,
"scs0009": SCS_SERIES_BAUDRATE_TABLE,
"sm8512bl": SM_SERIES_BAUDRATE_TABLE,
}
# High number of retries is needed for feetech compared to dynamixel motors.
NUM_READ_RETRY = 20
NUM_READ_RETRY = 50
NUM_WRITE_RETRY = 20
@@ -273,12 +422,18 @@ class FeetechMotorsBus:
self,
port: str,
motors: dict[str, tuple[int, str]],
group_sync_read: bool = True,
group_sync_write: bool = True,
protocol_version: int = 0,
extra_model_control_table: dict[str, list[tuple]] | None = None,
extra_model_resolution: dict[str, int] | None = None,
mock=False,
):
self.port = port
self.motors = motors
self.group_sync_read = group_sync_read
self.group_sync_write = group_sync_write
self.protocol_version = protocol_version
self.mock = mock
self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
@@ -311,7 +466,7 @@ class FeetechMotorsBus:
import scservo_sdk as scs
self.port_handler = scs.PortHandler(self.port)
self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
self.packet_handler = scs.PacketHandler(self.protocol_version)
try:
if not self.port_handler.openPort():
@@ -335,7 +490,7 @@ class FeetechMotorsBus:
import scservo_sdk as scs
self.port_handler = scs.PortHandler(self.port)
self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
self.packet_handler = scs.PacketHandler(self.protocol_version)
if not self.port_handler.openPort():
raise OSError(f"Failed to open port '{self.port}'.")
@@ -661,6 +816,8 @@ class FeetechMotorsBus:
else:
import scservo_sdk as scs
scs.SCS_SETEND(self.protocol_version)
return_list = True
if not isinstance(motor_ids, list):
return_list = False
@@ -699,6 +856,8 @@ class FeetechMotorsBus:
else:
import scservo_sdk as scs
scs.SCS_SETEND(self.protocol_version)
if not self.is_connected:
raise RobotDeviceNotConnectedError(
f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
@@ -721,31 +880,51 @@ class FeetechMotorsBus:
assert_same_address(self.model_ctrl_table, models, data_name)
addr, bytes = self.model_ctrl_table[model][data_name]
group_key = get_group_sync_key(data_name, motor_names)
if data_name not in self.group_readers:
# create new group reader
self.group_readers[group_key] = scs.GroupSyncRead(
self.port_handler, self.packet_handler, addr, bytes
)
if self.group_sync_read:
group_key = get_group_sync_key(data_name, motor_names)
if data_name not in self.group_readers:
# create new group reader
self.group_readers[group_key] = scs.GroupSyncRead(
self.port_handler, self.packet_handler, addr, bytes
)
for idx in motor_ids:
self.group_readers[group_key].addParam(idx)
for _ in range(NUM_READ_RETRY):
comm = self.group_readers[group_key].txRxPacket()
if comm == scs.COMM_SUCCESS:
break
if comm != scs.COMM_SUCCESS:
raise ConnectionError(
f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
f"{self.packet_handler.getTxRxResult(comm)}"
)
values = []
for idx in motor_ids:
self.group_readers[group_key].addParam(idx)
value = self.group_readers[group_key].getData(idx, addr, bytes)
values.append(value)
else:
values = []
for idx in motor_ids:
if bytes == 1:
value, comm, error = self.packet_handler.read1ByteTxRx(self.port_handler, idx, addr)
elif bytes == 2:
value, comm, error = self.packet_handler.read2ByteTxRx(self.port_handler, idx, addr)
elif bytes == 4:
value, comm, error = self.packet_handler.read4ByteTxRx(self.port_handler, idx, addr)
else:
raise ValueError(bytes)
for _ in range(NUM_READ_RETRY):
comm = self.group_readers[group_key].txRxPacket()
if comm == scs.COMM_SUCCESS:
break
if comm != scs.COMM_SUCCESS:
raise ConnectionError(self.packet_handler.getTxRxResult(comm))
elif error != 0:
raise ConnectionError(self.packet_handler.getRxPacketError(error))
if comm != scs.COMM_SUCCESS:
raise ConnectionError(
f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
f"{self.packet_handler.getTxRxResult(comm)}"
)
values = []
for idx in motor_ids:
value = self.group_readers[group_key].getData(idx, addr, bytes)
values.append(value)
values.append(value)
values = np.array(values)
@@ -775,6 +954,8 @@ class FeetechMotorsBus:
else:
import scservo_sdk as scs
scs.SCS_SETEND(self.protocol_version)
if not isinstance(motor_ids, list):
motor_ids = [motor_ids]
if not isinstance(values, list):
@@ -811,6 +992,8 @@ class FeetechMotorsBus:
else:
import scservo_sdk as scs
scs.SCS_SETEND(self.protocol_version)
if motor_names is None:
motor_names = self.motor_names
@@ -836,27 +1019,31 @@ class FeetechMotorsBus:
assert_same_address(self.model_ctrl_table, models, data_name)
addr, bytes = self.model_ctrl_table[model][data_name]
group_key = get_group_sync_key(data_name, motor_names)
init_group = data_name not in self.group_readers
if init_group:
self.group_writers[group_key] = scs.GroupSyncWrite(
self.port_handler, self.packet_handler, addr, bytes
)
if self.group_sync_write:
group_key = get_group_sync_key(data_name, motor_names)
for idx, value in zip(motor_ids, values, strict=True):
data = convert_to_bytes(value, bytes, self.mock)
init_group = data_name not in self.group_readers
if init_group:
self.group_writers[group_key].addParam(idx, data)
else:
self.group_writers[group_key].changeParam(idx, data)
self.group_writers[group_key] = scs.GroupSyncWrite(
self.port_handler, self.packet_handler, addr, bytes
)
comm = self.group_writers[group_key].txPacket()
if comm != scs.COMM_SUCCESS:
raise ConnectionError(
f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
f"{self.packet_handler.getTxRxResult(comm)}"
)
for idx, value in zip(motor_ids, values, strict=True):
data = convert_to_bytes(value, bytes, self.mock)
if init_group:
self.group_writers[group_key].addParam(idx, data)
else:
self.group_writers[group_key].changeParam(idx, data)
comm = self.group_writers[group_key].txPacket()
if comm != scs.COMM_SUCCESS:
raise ConnectionError(
f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
f"{self.packet_handler.getTxRxResult(comm)}"
)
else:
raise NotImplementedError()
# log the number of seconds it took to write the data to the motors
delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)

View File

@@ -306,16 +306,16 @@ def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str
calib = {}
print("Calibrate shoulder_pan")
calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan", load_threshold=350, count_threshold=200)
calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan")
arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan")
time.sleep(1)
print("Calibrate gripper")
calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True, count_threshold=200)
calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True)
time.sleep(1)
print("Calibrate wrist_flex")
calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex", invert_drive_mode=True, count_threshold=200)
calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex", invert_drive_mode=True)
calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=-210 + 1024)
wr_pos = arm.read("Present_Position", "wrist_roll")
@@ -329,7 +329,7 @@ def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str
time.sleep(1)
print("Calibrate wrist_roll")
calib["wrist_roll"] = move_to_calibrate(arm, "wrist_roll", invert_drive_mode=True, count_threshold=200)
calib["wrist_roll"] = move_to_calibrate(arm, "wrist_roll", invert_drive_mode=True)
calib["wrist_roll"] = apply_offset(calib["wrist_roll"], offset=790)
arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"] - 1024, "wrist_roll")
@@ -348,7 +348,6 @@ def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str
arm,
"elbow_flex",
invert_drive_mode=True,
count_threshold=200,
in_between_move_hook=in_between_move_elbow_flex_hook,
)
arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex")

File diff suppressed because it is too large Load Diff

View File

@@ -504,7 +504,7 @@ class ManipulatorRobot:
# Used when record_data=True
follower_goal_pos[name] = goal_pos
goal_pos = goal_pos.numpy().astype(np.int32)
goal_pos = goal_pos.numpy().astype(np.float32)
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
@@ -626,7 +626,7 @@ class ManipulatorRobot:
action_sent.append(goal_pos)
# Send goal position to each follower
goal_pos = goal_pos.numpy().astype(np.int32)
goal_pos = goal_pos.numpy().astype(np.float32)
self.follower_arms[name].write("Goal_Position", goal_pos)
return torch.cat(action_sent)

10
lerobot/configs/env/hopejr_real.yaml vendored Normal file
View File

@@ -0,0 +1,10 @@
# @package _global_
fps: 30
env:
name: real_world
task: null
state_dim: 16
action_dim: 16
fps: ${fps}

View File

@@ -0,0 +1,97 @@
# @package _global_
# Use `act_koch_real.yaml` to train on real-world datasets collected on Alexander Koch's robots.
# Compared to `act.yaml`, it contains 2 cameras (i.e. laptop, phone) instead of 1 camera (i.e. top).
# Also, `training.eval_freq` is set to -1. This config is used to evaluate checkpoints at a certain frequency of training steps.
# When it is set to -1, it deactivates evaluation. This is because real-world evaluation is done through our `control_robot.py` script.
# Look at the documentation in header of `control_robot.py` for more information on how to collect data , train and evaluate a policy.
#
# Example of usage for training:
# ```bash
# python lerobot/scripts/train.py \
# policy=act_koch_real \
# env=koch_real
# ```
seed: 1000
dataset_repo_id: nepyope/hopejr_test
override_dataset_stats:
observation.images.phone:
# stats from imagenet, since we use a pretrained vision model
mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1)
std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1)
training:
offline_steps: 80000
online_steps: 0
eval_freq: -1
save_freq: 10000
log_freq: 100
save_checkpoint: true
batch_size: 8
lr: 1e-5
lr_backbone: 1e-5
weight_decay: 1e-4
grad_clip_norm: 10
online_steps_between_rollouts: 1
delta_timestamps:
action: "[i / ${fps} for i in range(${policy.chunk_size})]"
eval:
n_episodes: 50
batch_size: 50
# See `configuration_act.py` for more details.
policy:
name: act
# Input / output structure.
n_obs_steps: 1
chunk_size: 100
n_action_steps: 100
input_shapes:
# TODO(rcadene, alexander-soare): add variables for height and width from the dataset/env?
observation.images.phone: [3, 480, 640]
observation.state: ["${env.state_dim}"]
output_shapes:
action: ["${env.action_dim}"]
# Normalization / Unnormalization
input_normalization_modes:
observation.images.phone: mean_std
observation.state: mean_std
output_normalization_modes:
action: mean_std
# Architecture.
# Vision backbone.
vision_backbone: resnet18
pretrained_backbone_weights: ResNet18_Weights.IMAGENET1K_V1
replace_final_stride_with_dilation: false
# Transformer layers.
pre_norm: false
dim_model: 512
n_heads: 8
dim_feedforward: 3200
feedforward_activation: relu
n_encoder_layers: 4
# Note: Although the original ACT implementation has 7 for `n_decoder_layers`, there is a bug in the code
# that means only the first layer is used. Here we match the original implementation by setting this to 1.
# See this issue https://github.com/tonyzhaozh/act/issues/25#issue-2258740521.
n_decoder_layers: 1
# VAE.
use_vae: true
latent_dim: 32
n_vae_encoder_layers: 4
# Inference.
temporal_ensemble_momentum: null
# Training and loss computation.
dropout: 0.1
kl_weight: 10.0

View File

@@ -0,0 +1,73 @@
# [SO-100 robot arm](https://github.com/TheRobotStudio/SO-ARM100)
# Requires installing extras packages
# With pip: `pip install -e ".[feetech]"`
# With poetry: `poetry install --sync --extras "feetech"`
# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/10_use_so100.md)
_target_: lerobot.common.robot_devices.robots.hopejr.HopeJrRobot
# robot_type: hopejr
# calibration_dir: .cache/calibration/hopejr
# # `max_relative_target` limits 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.
# max_relative_target: null
# leader_arms:
# main:
# _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus
# port: /dev/tty.usbmodem585A0077581
# motors:
# # name: (index, model)
# shoulder_pan: [1, "sts3215"]
# shoulder_lift: [2, "sts3215"]
# elbow_flex: [3, "sts3215"]
# wrist_flex: [4, "sts3215"]
# wrist_roll: [5, "sts3215"]
# gripper: [6, "sts3215"]
# follower_arms:
# main:
# _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus
# port: /dev/tty.usbserial-2130
# motors:
# # name: (index, model)
# shoulder_pitch: [1, "sts3250"]
# shoulder_yaw: [2, "sts3215"] # TODO: sts3250
# shoulder_roll: [3, "sts3215"] # TODO: sts3250
# elbow_flex: [4, "sts3250"]
# wrist_roll: [5, "sts3215"]
# wrist_yaw: [6, "sts3215"]
# wrist_pitch: [7, "sts3215"]
# thumb_basel_rotation: [30, "scs0009"]
# thumb_flexion: [27, "scs0009"]
# thumb_pinky_side: [26, "scs0009"]
# thumb_thumb_side: [28, "scs0009"]
# index_flexor: [25, "scs0009"]
# index_pinky_side: [31, "scs0009"]
# index_thumb_side: [32, "scs0009"]
# middle_flexor: [24, "scs0009"]
# middle_pinky_side: [33, "scs0009"]
# middle_thumb_side: [34, "scs0009"]
# ring_flexor: [21, "scs0009"]
# ring_pinky_side: [36, "scs0009"]
# ring_thumb_side: [35, "scs0009"]
# pinky_flexor: [23, "scs0009"]
# pinky_pinky_side: [38, "scs0009"]
# pinky_thumb_side: [37, "scs0009"]
cameras:
# laptop:
# _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera
# camera_index: 0
# fps: 30
# width: 640
# height: 480
phone:
_target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera
camera_index: 0
fps: 30
width: 640
height: 480

View File

@@ -225,7 +225,8 @@ def record(
# Load pretrained policy
if pretrained_policy_name_or_path is not None:
policy, policy_fps, device, use_amp = init_policy(pretrained_policy_name_or_path, policy_overrides)
device="mps"
policy.to(device)
if fps is None:
fps = policy_fps
logging.warning(f"No fps provided, so using the fps from policy config ({policy_fps}).")
@@ -258,7 +259,7 @@ def record(
# 3. place the cameras windows on screen
enable_teleoperation = policy is None
log_say("Warmup record", play_sounds)
warmup_record(robot, events, enable_teleoperation, warmup_time_s, display_cameras, fps)
# warmup_record(robot, events, enable_teleoperation, warmup_time_s, display_cameras, fps)
if has_method(robot, "teleop_safety_stop"):
robot.teleop_safety_stop()
@@ -509,6 +510,7 @@ if __name__ == "__main__":
del kwargs["robot_path"]
del kwargs["robot_overrides"]
robot_cfg = init_hydra_config(robot_path, robot_overrides)
robot = make_robot(robot_cfg)

Binary file not shown.

After

Width:  |  Height:  |  Size: 43 KiB

174
servo_log.txt Normal file
View File

@@ -0,0 +1,174 @@
Logging parameters for servo: shoulder_pitch
Duration: 2s, Interval: 0.1s
==================================================
Timestamp: 0.000
Present_Current = [19]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [123]
Present_Load = [123]
Present_Position = [1803]
--------------------------------------------------
Timestamp: 0.105
Present_Current = [51]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [121]
Present_Load = [207]
Present_Position = [1742]
--------------------------------------------------
Timestamp: 0.211
Present_Current = [130]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [120]
Present_Load = [363]
Present_Position = [1668]
--------------------------------------------------
Timestamp: 0.316
Present_Current = [192]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [120]
Present_Load = [471]
Present_Position = [1564]
--------------------------------------------------
Timestamp: 0.422
Present_Current = [177]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [120]
Present_Load = [503]
Present_Position = [1428]
--------------------------------------------------
Timestamp: 0.528
Present_Current = [294]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [118]
Present_Load = [615]
Present_Position = [1282]
--------------------------------------------------
Timestamp: 0.633
Present_Current = [360]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [118]
Present_Load = [671]
Present_Position = [1141]
--------------------------------------------------
Timestamp: 0.739
Present_Current = [360]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [118]
Present_Load = [639]
Present_Position = [1012]
--------------------------------------------------
Timestamp: 0.845
Present_Current = [348]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [118]
Present_Load = [615]
Present_Position = [907]
--------------------------------------------------
Timestamp: 0.951
Present_Current = [407]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [118]
Present_Load = [643]
Present_Position = [830]
--------------------------------------------------
Timestamp: 1.057
Present_Current = [479]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [38]
Present_Voltage = [117]
Present_Load = [679]
Present_Position = [776]
--------------------------------------------------
Timestamp: 1.163
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [947]
--------------------------------------------------
Timestamp: 1.269
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [1136]
--------------------------------------------------
Timestamp: 1.375
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [1438]
--------------------------------------------------
Timestamp: 1.481
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [1782]
--------------------------------------------------
Timestamp: 1.587
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [1949]
--------------------------------------------------
Timestamp: 1.693
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [2042]
--------------------------------------------------
Timestamp: 1.799
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [2049]
--------------------------------------------------
Timestamp: 1.906
Present_Current = [0]
Protection_Current = [310]
Over_Current_Protection_Time = [50]
Present_Temperature = [37]
Present_Voltage = [122]
Present_Load = [0]
Present_Position = [1997]
--------------------------------------------------

1107
shoulder_pitch_fail.txt Normal file

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 64 KiB

BIN
shoulder_pitch_log_50ms.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

View File

@@ -18,6 +18,10 @@ def convert_to_bytes(value, bytes):
return value
def SCS_SETEND(protocol_version):
del protocol_version
def get_default_motor_values(motor_index):
return {
# Key (int) are from SCS_SERIES_CONTROL_TABLE