Skip to content

Commit 101fb02

Browse files
Add gravity compensation to the openarms teleoperation (#2352)
* adding first attempt at gcompensation to open arms * add teleop with gravity compensation script
1 parent 0664add commit 101fb02

File tree

2 files changed

+389
-0
lines changed

2 files changed

+389
-0
lines changed
Lines changed: 157 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,157 @@
1+
import time
2+
import numpy as np
3+
import pinocchio as pin
4+
from os.path import join, dirname, exists, expanduser
5+
6+
from lerobot.robots.openarms.openarms_follower import OpenArmsFollower
7+
from lerobot.robots.openarms.config_openarms_follower import OpenArmsFollowerConfig
8+
9+
10+
def main() -> None:
11+
config = OpenArmsFollowerConfig(
12+
port_right="can0",
13+
port_left="can1",
14+
can_interface="socketcan",
15+
id="openarms_follower",
16+
disable_torque_on_disconnect=True,
17+
max_relative_target=5.0,
18+
)
19+
20+
21+
print("Initializing robot...")
22+
follower = OpenArmsFollower(config)
23+
follower.connect(calibrate=True)
24+
25+
# Load URDF for Pinocchio dynamics
26+
urdf_path = "/home/croissant/Documents/openarm_description/openarm_bimanual_pybullet.urdf"
27+
28+
pin_robot = pin.RobotWrapper.BuildFromURDF(urdf_path, dirname(urdf_path))
29+
pin_robot.data = pin_robot.model.createData()
30+
print(f"✓ Loaded Pinocchio model with {pin_robot.nq} DoFs")
31+
32+
follower.pin_robot = pin_robot
33+
34+
control_arm = "right"
35+
36+
print(f"Applying gravity compensation to: {control_arm.upper()} ARM (all joints)")
37+
print("\nAll joints on the right arm will have gravity compensation applied.")
38+
print("Left arm joints will be disabled (free to move).")
39+
print("\nIMPORTANT:")
40+
print(" 1. Support the arm before starting")
41+
print(" 2. The arm will be held in place by gravity compensation")
42+
print(" 3. You should be able to move it with gentle force")
43+
print("\nPress ENTER when ready to start...")
44+
input()
45+
46+
follower.bus_left.enable_torque()
47+
time.sleep(0.1)
48+
49+
print(f"✓ Motors enabled")
50+
print(f" {control_arm.upper()} arm: Gravity compensation active")
51+
print(f" LEFT arm: Zero torque (free to move)")
52+
53+
print("\nStarting gravity compensation loop...")
54+
print("Press Ctrl+C to stop\n")
55+
56+
loop_times = []
57+
last_print_time = time.perf_counter()
58+
59+
try:
60+
while True:
61+
loop_start = time.perf_counter()
62+
63+
# Get current joint positions from robot
64+
obs = follower.get_observation()
65+
66+
# Extract positions in degrees
67+
positions_deg = {}
68+
for motor in follower.bus_right.motors:
69+
key = f"right_{motor}.pos"
70+
if key in obs:
71+
positions_deg[f"right_{motor}"] = obs[key]
72+
73+
for motor in follower.bus_left.motors:
74+
key = f"left_{motor}.pos"
75+
if key in obs:
76+
positions_deg[f"left_{motor}"] = obs[key]
77+
78+
# Convert to radians and calculate gravity torques
79+
# Use the built-in method from OpenArmsFollower
80+
positions_rad = {k: np.deg2rad(v) for k, v in positions_deg.items()}
81+
torques_nm = follower._gravity_from_q(positions_rad)
82+
83+
# Apply gravity compensation torques to all joints on the right arm
84+
for motor in follower.bus_right.motors:
85+
full_name = f"right_{motor}"
86+
position = positions_deg.get(full_name, 0.0)
87+
88+
# Apply gravity compensation to this joint
89+
torque = torques_nm.get(full_name, 0.0)
90+
91+
# Send MIT control command with gravity compensation torque
92+
follower.bus_right._mit_control(
93+
motor=motor,
94+
kp=0.0, # No position control
95+
kd=0.0, # No velocity damping
96+
position_degrees=position,
97+
velocity_deg_per_sec=0.0,
98+
torque=torque
99+
)
100+
101+
# Also ensure left arm joints have zero torque
102+
for motor in follower.bus_left.motors:
103+
full_name = f"left_{motor}"
104+
position = positions_deg.get(full_name, 0.0)
105+
106+
follower.bus_left._mit_control(
107+
motor=motor,
108+
kp=0.0,
109+
kd=0.0,
110+
position_degrees=position,
111+
velocity_deg_per_sec=0.0,
112+
torque=0.0
113+
)
114+
115+
# Measure loop time
116+
loop_end = time.perf_counter()
117+
loop_time = loop_end - loop_start
118+
loop_times.append(loop_time)
119+
120+
# Print status every 2 seconds
121+
if loop_end - last_print_time >= 2.0:
122+
if loop_times:
123+
avg_time = sum(loop_times) / len(loop_times)
124+
current_hz = 1.0 / avg_time if avg_time > 0 else 0
125+
126+
# Display status for all joints on the controlled arm
127+
print(f"\n[RIGHT ARM] Loop: {current_hz:.1f} Hz ({avg_time*1000:.1f} ms)")
128+
129+
# Show each joint's position and torque
130+
for motor in follower.bus_right.motors:
131+
full_name = f"right_{motor}"
132+
pos = positions_deg.get(full_name, 0.0)
133+
torque = torques_nm.get(full_name, 0.0)
134+
print(f" {motor:8s}: Pos={pos:7.1f}° | Torque={torque:7.3f} N·m")
135+
136+
# Reset for next measurement window
137+
loop_times = []
138+
last_print_time = loop_end
139+
140+
# Small sleep to avoid overwhelming the CAN bus
141+
time.sleep(0.01) # 100 Hz
142+
143+
except KeyboardInterrupt:
144+
print("\n\nStopping gravity compensation...")
145+
146+
finally:
147+
print("\nDisabling all motors and disconnecting...")
148+
follower.bus_right.disable_torque()
149+
follower.bus_left.disable_torque()
150+
time.sleep(0.1)
151+
follower.disconnect()
152+
print("✓ Safe shutdown complete")
153+
154+
155+
if __name__ == "__main__":
156+
main()
157+
Lines changed: 232 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,232 @@
1+
"""
2+
OpenArms Teleoperation with Gravity Compensation
3+
4+
Leader RIGHT arm: Gravity compensation (weightless, easy to move)
5+
Follower RIGHT arm: Mirrors leader movements
6+
Both LEFT arms: Free to move (disabled)
7+
8+
The urdf file tested with this script is found in:
9+
https://github.com/michel-aractingi/openarm_description/blob/main/openarm_bimanual_pybullet.urdf
10+
"""
11+
12+
import time
13+
import os
14+
15+
import numpy as np
16+
import pinocchio as pin
17+
18+
from lerobot.robots.openarms.config_openarms_follower import OpenArmsFollowerConfig
19+
from lerobot.robots.openarms.openarms_follower import OpenArmsFollower
20+
from lerobot.teleoperators.openarms.config_openarms_leader import OpenArmsLeaderConfig
21+
from lerobot.teleoperators.openarms.openarms_leader import OpenArmsLeader
22+
23+
# Path to the URDF file
24+
URDF_PATH = "/home/croissant/Documents/openarm_description/openarm_bimanual_pybullet.urdf"
25+
26+
def compute_gravity_torques(leader, positions_rad):
27+
"""
28+
Compute gravity torques for all joints in the robot.
29+
30+
Args:
31+
leader: OpenArmsLeader instance with pin_robot set
32+
positions_rad: Dictionary mapping motor names (with arm prefix) to positions in radians
33+
34+
Returns:
35+
Dictionary mapping motor names to gravity torques in N·m
36+
"""
37+
if not hasattr(leader, "pin_robot") or leader.pin_robot is None:
38+
raise RuntimeError("URDF model not loaded on leader")
39+
40+
# Build position vector in the order of motors (right arm, then left arm)
41+
q = np.zeros(leader.pin_robot.model.nq)
42+
idx = 0
43+
44+
# Right arm motors
45+
for motor_name in leader.bus_right.motors:
46+
full_name = f"right_{motor_name}"
47+
q[idx] = positions_rad.get(full_name, 0.0)
48+
idx += 1
49+
50+
# Left arm motors
51+
for motor_name in leader.bus_left.motors:
52+
full_name = f"left_{motor_name}"
53+
q[idx] = positions_rad.get(full_name, 0.0)
54+
idx += 1
55+
56+
# Compute generalized gravity vector
57+
g = pin.computeGeneralizedGravity(leader.pin_robot.model, leader.pin_robot.data, q)
58+
59+
# Map back to motor names
60+
result = {}
61+
idx = 0
62+
for motor_name in leader.bus_right.motors:
63+
result[f"right_{motor_name}"] = float(g[idx])
64+
idx += 1
65+
for motor_name in leader.bus_left.motors:
66+
result[f"left_{motor_name}"] = float(g[idx])
67+
idx += 1
68+
69+
return result
70+
71+
72+
def main():
73+
"""Main teleoperation loop with gravity compensation"""
74+
75+
print("=" * 70)
76+
print("OpenArms Teleoperation with Gravity Compensation")
77+
print("=" * 70)
78+
79+
# Configuration
80+
follower_config = OpenArmsFollowerConfig(
81+
port_right="can0",
82+
port_left="can1",
83+
can_interface="socketcan",
84+
id="openarms_follower",
85+
disable_torque_on_disconnect=True,
86+
max_relative_target=10.0,
87+
)
88+
89+
leader_config = OpenArmsLeaderConfig(
90+
port_right="can2",
91+
port_left="can3",
92+
can_interface="socketcan",
93+
id="openarms_leader",
94+
manual_control=False, # Enable torque control for gravity compensation
95+
)
96+
97+
# Initialize and connect
98+
print("\nInitializing devices...")
99+
follower = OpenArmsFollower(follower_config)
100+
leader = OpenArmsLeader(leader_config)
101+
102+
follower.connect(calibrate=True)
103+
leader.connect(calibrate=True)
104+
105+
# Load URDF for gravity compensation
106+
if not os.path.exists(URDF_PATH):
107+
raise FileNotFoundError(f"URDF file not found at {URDF_PATH}")
108+
pin_robot = pin.RobotWrapper.BuildFromURDF(URDF_PATH, os.path.dirname(URDF_PATH))
109+
pin_robot.data = pin_robot.model.createData()
110+
leader.pin_robot = pin_robot
111+
112+
print("\nLeader RIGHT: G-comp | Follower RIGHT: Teleop")
113+
print("Press ENTER to start...")
114+
input()
115+
116+
# Enable motors
117+
leader.bus_right.enable_torque()
118+
leader.bus_left.enable_torque()
119+
time.sleep(0.1)
120+
121+
print("Press Ctrl+C to stop\n")
122+
123+
# Main control loop
124+
loop_times = []
125+
last_print_time = time.perf_counter()
126+
127+
# Right arm joints only
128+
right_joints = [
129+
"right_joint_1",
130+
"right_joint_2",
131+
"right_joint_3",
132+
"right_joint_4",
133+
"right_joint_5",
134+
"right_joint_6",
135+
"right_joint_7",
136+
"right_gripper",
137+
]
138+
139+
try:
140+
while True:
141+
loop_start = time.perf_counter()
142+
143+
# Get leader state
144+
leader_action = leader.get_action()
145+
146+
leader_positions_deg = {}
147+
for motor in leader.bus_right.motors:
148+
key = f"right_{motor}.pos"
149+
if key in leader_action:
150+
leader_positions_deg[f"right_{motor}"] = leader_action[key]
151+
152+
for motor in leader.bus_left.motors:
153+
key = f"left_{motor}.pos"
154+
if key in leader_action:
155+
leader_positions_deg[f"left_{motor}"] = leader_action[key]
156+
157+
# Calculate gravity torques for leader
158+
leader_positions_rad = {k: np.deg2rad(v) for k, v in leader_positions_deg.items()}
159+
leader_torques_nm = compute_gravity_torques(leader, leader_positions_rad)
160+
161+
# Apply gravity compensation to leader right arm
162+
for motor in leader.bus_right.motors:
163+
full_name = f"right_{motor}"
164+
position = leader_positions_deg.get(full_name, 0.0)
165+
torque = leader_torques_nm.get(full_name, 0.0)
166+
167+
leader.bus_right._mit_control(
168+
motor=motor,
169+
kp=0.0,
170+
kd=0.0,
171+
position_degrees=position,
172+
velocity_deg_per_sec=0.0,
173+
torque=torque,
174+
)
175+
176+
# Keep leader left arm free
177+
for motor in leader.bus_left.motors:
178+
full_name = f"left_{motor}"
179+
position = leader_positions_deg.get(full_name, 0.0)
180+
181+
leader.bus_left._mit_control(
182+
motor=motor,
183+
kp=0.0,
184+
kd=0.0,
185+
position_degrees=position,
186+
velocity_deg_per_sec=0.0,
187+
torque=0.0,
188+
)
189+
190+
# Send leader positions to follower right arm
191+
follower_action = {}
192+
for joint in right_joints:
193+
pos_key = f"{joint}.pos"
194+
if pos_key in leader_action:
195+
follower_action[pos_key] = leader_action[pos_key]
196+
197+
if follower_action:
198+
follower.send_action(follower_action)
199+
200+
# Performance monitoring
201+
loop_end = time.perf_counter()
202+
loop_time = loop_end - loop_start
203+
loop_times.append(loop_time)
204+
205+
if loop_end - last_print_time >= 2.0:
206+
if loop_times:
207+
avg_time = sum(loop_times) / len(loop_times)
208+
current_hz = 1.0 / avg_time if avg_time > 0 else 0
209+
sample_pos = leader_positions_deg.get("right_joint_2", 0.0)
210+
sample_torque = leader_torques_nm.get("right_joint_2", 0.0)
211+
212+
print(f"[{current_hz:.1f} Hz] J2: {sample_pos:5.1f}° | Torque: {sample_torque:5.2f} N·m")
213+
214+
loop_times = []
215+
last_print_time = loop_end
216+
217+
except KeyboardInterrupt:
218+
print("\n\nStopping...")
219+
finally:
220+
try:
221+
leader.bus_right.disable_torque()
222+
leader.bus_left.disable_torque()
223+
time.sleep(0.1)
224+
leader.disconnect()
225+
follower.disconnect()
226+
print("✓ Shutdown complete")
227+
except Exception as e:
228+
print(f"Shutdown error: {e}")
229+
230+
231+
if __name__ == "__main__":
232+
main()

0 commit comments

Comments
 (0)