Update UR5e robot configurations and UI for gripper control and home position
Browse files- Adjusted gripper control values in mujoco_server.py and UR5 environment to align with the Robotiq 2F-85 specifications (0=open, 255=closed).
- Updated the default home position for the UR5e to reflect the official MuJoCo Menagerie configuration.
- Enhanced UI elements for joint sliders and gripper display to synchronize with actual positions and improve user experience.
- Added functionality to restore saved robot selections from local storage in the UI.
- mujoco_server.py +54 -34
- robots/ur5/model/scene.xml +3 -2
- robots/ur5/ur5_env.py +12 -12
mujoco_server.py
CHANGED
|
@@ -385,12 +385,11 @@ def handle_ws_message(data):
|
|
| 385 |
elif msg_type == 'gripper':
|
| 386 |
payload = data.get('data', {})
|
| 387 |
action = payload.get('action', 'open')
|
| 388 |
-
# Robotiq 2F-85:
|
| 389 |
-
# Control range 0-255 maps to joint angle 0-0.8 rad
|
| 390 |
if action == 'open':
|
| 391 |
-
value =
|
| 392 |
elif action == 'close':
|
| 393 |
-
value =
|
| 394 |
else:
|
| 395 |
value = payload.get('value', 128)
|
| 396 |
with mujoco_lock:
|
|
@@ -572,22 +571,21 @@ def index():
|
|
| 572 |
}
|
| 573 |
.camera-panel .control-group { margin-bottom: 10px; }
|
| 574 |
.camera-panel .control-group:last-child { margin-bottom: 0; }
|
| 575 |
-
/* Collapsible panel header */
|
| 576 |
.panel-header {
|
| 577 |
display: flex; justify-content: space-between; align-items: center;
|
| 578 |
cursor: pointer; margin-bottom: 15px;
|
|
|
|
| 579 |
}
|
| 580 |
-
.panel-header
|
| 581 |
-
.
|
| 582 |
-
|
| 583 |
-
|
| 584 |
-
|
| 585 |
-
|
| 586 |
-
|
| 587 |
-
display: flex; align-items: center; justify-content: center;
|
| 588 |
-
font-size: 1.1em; transition: all 0.2s;
|
| 589 |
}
|
| 590 |
-
.
|
| 591 |
.panel-content { transition: all 0.3s ease; overflow: hidden; }
|
| 592 |
.panel-content.collapsed { max-height: 0; opacity: 0; margin: 0; padding: 0; }
|
| 593 |
.overlay.collapsed { width: auto; min-width: 200px; }
|
|
@@ -701,14 +699,12 @@ def index():
|
|
| 701 |
</div>
|
| 702 |
|
| 703 |
<div class="overlay" id="control_panel">
|
| 704 |
-
<div class="panel-header" onclick="togglePanel()">
|
| 705 |
<h2 id="robot_title">Unitree G1 Humanoid</h2>
|
| 706 |
-
<button class="collapse-btn" id="collapse_btn">-</button>
|
| 707 |
</div>
|
| 708 |
|
| 709 |
<div class="panel-content" id="panel_content">
|
| 710 |
<div class="robot-selector">
|
| 711 |
-
<label>Select Robot</label>
|
| 712 |
<select id="robot_select" onchange="switchRobot()">
|
| 713 |
<option value="g1">Unitree G1 (Humanoid)</option>
|
| 714 |
<option value="spot">Boston Dynamics Spot (Quadruped)</option>
|
|
@@ -806,27 +802,27 @@ def index():
|
|
| 806 |
<div class="joint-sliders">
|
| 807 |
<div class="slider-row">
|
| 808 |
<label>J1</label>
|
| 809 |
-
<input type="range" id="joint_0" min="-6.28" max="6.28" step="0.01" value="
|
| 810 |
-
<span class="val-display" id="joint_0_val">
|
| 811 |
</div>
|
| 812 |
<div class="slider-row">
|
| 813 |
<label>J2</label>
|
| 814 |
-
<input type="range" id="joint_1" min="-6.28" max="6.28" step="0.01" value="-
|
| 815 |
-
<span class="val-display" id="joint_1_val">-
|
| 816 |
</div>
|
| 817 |
<div class="slider-row">
|
| 818 |
<label>J3</label>
|
| 819 |
-
<input type="range" id="joint_2" min="-3.14" max="3.14" step="0.01" value="
|
| 820 |
-
<span class="val-display" id="joint_2_val">
|
| 821 |
</div>
|
| 822 |
<div class="slider-row">
|
| 823 |
<label>J4</label>
|
| 824 |
-
<input type="range" id="joint_3" min="-6.28" max="6.28" step="0.01" value="-1.
|
| 825 |
<span class="val-display" id="joint_3_val">-1.57</span>
|
| 826 |
</div>
|
| 827 |
<div class="slider-row">
|
| 828 |
<label>J5</label>
|
| 829 |
-
<input type="range" id="joint_4" min="-6.28" max="6.28" step="0.01" value="-1.
|
| 830 |
<span class="val-display" id="joint_4_val">-1.57</span>
|
| 831 |
</div>
|
| 832 |
<div class="slider-row">
|
|
@@ -894,6 +890,13 @@ def index():
|
|
| 894 |
clearInterval(reconnectTimer);
|
| 895 |
reconnectTimer = null;
|
| 896 |
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 897 |
};
|
| 898 |
|
| 899 |
ws.onclose = () => {
|
|
@@ -933,16 +936,32 @@ def index():
|
|
| 933 |
euler[0].toFixed(2) + ', ' + euler[1].toFixed(2) + ', ' + euler[2].toFixed(2);
|
| 934 |
}
|
| 935 |
|
| 936 |
-
// Gripper: 0=
|
| 937 |
document.getElementById('gripper_val').innerText =
|
| 938 |
-
(data.gripper / 255 * 100).toFixed(0) + '% open';
|
| 939 |
document.getElementById('arm_step_val').innerText = data.steps;
|
| 940 |
|
| 941 |
-
// Update joint position display
|
| 942 |
if (data.joint_positions) {
|
| 943 |
const jp = data.joint_positions;
|
| 944 |
document.getElementById('joint_pos_display').innerText =
|
| 945 |
jp.map(j => j.toFixed(2)).join(', ');
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 946 |
}
|
| 947 |
|
| 948 |
// Update control mode display
|
|
@@ -1036,21 +1055,22 @@ def index():
|
|
| 1036 |
function togglePanel() {
|
| 1037 |
panelCollapsed = !panelCollapsed;
|
| 1038 |
const content = document.getElementById('panel_content');
|
| 1039 |
-
const
|
| 1040 |
const panel = document.getElementById('control_panel');
|
| 1041 |
if (panelCollapsed) {
|
| 1042 |
content.classList.add('collapsed');
|
| 1043 |
panel.classList.add('collapsed');
|
| 1044 |
-
|
| 1045 |
} else {
|
| 1046 |
content.classList.remove('collapsed');
|
| 1047 |
panel.classList.remove('collapsed');
|
| 1048 |
-
|
| 1049 |
}
|
| 1050 |
}
|
| 1051 |
|
| 1052 |
function switchRobot() {
|
| 1053 |
const robot = robotSelect.value;
|
|
|
|
| 1054 |
send('switch_robot', {robot});
|
| 1055 |
updateRobotUI(robot);
|
| 1056 |
}
|
|
@@ -1131,8 +1151,8 @@ def index():
|
|
| 1131 |
}
|
| 1132 |
|
| 1133 |
function goToHome() {
|
| 1134 |
-
//
|
| 1135 |
-
const home = [
|
| 1136 |
for (let i = 0; i < 6; i++) {
|
| 1137 |
document.getElementById('joint_' + i).value = home[i];
|
| 1138 |
document.getElementById('joint_' + i + '_val').innerText = home[i].toFixed(2);
|
|
|
|
| 385 |
elif msg_type == 'gripper':
|
| 386 |
payload = data.get('data', {})
|
| 387 |
action = payload.get('action', 'open')
|
| 388 |
+
# Robotiq 2F-85: 0 = open, 255 = closed (official MuJoCo Menagerie)
|
|
|
|
| 389 |
if action == 'open':
|
| 390 |
+
value = 0 # 0 = fully open
|
| 391 |
elif action == 'close':
|
| 392 |
+
value = 255 # 255 = fully closed
|
| 393 |
else:
|
| 394 |
value = payload.get('value', 128)
|
| 395 |
with mujoco_lock:
|
|
|
|
| 571 |
}
|
| 572 |
.camera-panel .control-group { margin-bottom: 10px; }
|
| 573 |
.camera-panel .control-group:last-child { margin-bottom: 0; }
|
| 574 |
+
/* Collapsible panel header - title is the button */
|
| 575 |
.panel-header {
|
| 576 |
display: flex; justify-content: space-between; align-items: center;
|
| 577 |
cursor: pointer; margin-bottom: 15px;
|
| 578 |
+
padding: 4px 0; border-radius: 4px; transition: all 0.2s;
|
| 579 |
}
|
| 580 |
+
.panel-header:hover { background: rgba(188, 190, 236, 0.1); }
|
| 581 |
+
.panel-header h2 {
|
| 582 |
+
margin: 0; display: flex; align-items: center; gap: 8px;
|
| 583 |
+
}
|
| 584 |
+
.panel-header h2::after {
|
| 585 |
+
content: '−'; font-weight: 300; font-size: 1.2em;
|
| 586 |
+
opacity: 0.6; transition: transform 0.2s;
|
|
|
|
|
|
|
| 587 |
}
|
| 588 |
+
.panel-header.collapsed h2::after { content: '+'; }
|
| 589 |
.panel-content { transition: all 0.3s ease; overflow: hidden; }
|
| 590 |
.panel-content.collapsed { max-height: 0; opacity: 0; margin: 0; padding: 0; }
|
| 591 |
.overlay.collapsed { width: auto; min-width: 200px; }
|
|
|
|
| 699 |
</div>
|
| 700 |
|
| 701 |
<div class="overlay" id="control_panel">
|
| 702 |
+
<div class="panel-header" id="panel_header" onclick="togglePanel()">
|
| 703 |
<h2 id="robot_title">Unitree G1 Humanoid</h2>
|
|
|
|
| 704 |
</div>
|
| 705 |
|
| 706 |
<div class="panel-content" id="panel_content">
|
| 707 |
<div class="robot-selector">
|
|
|
|
| 708 |
<select id="robot_select" onchange="switchRobot()">
|
| 709 |
<option value="g1">Unitree G1 (Humanoid)</option>
|
| 710 |
<option value="spot">Boston Dynamics Spot (Quadruped)</option>
|
|
|
|
| 802 |
<div class="joint-sliders">
|
| 803 |
<div class="slider-row">
|
| 804 |
<label>J1</label>
|
| 805 |
+
<input type="range" id="joint_0" min="-6.28" max="6.28" step="0.01" value="-1.5708" oninput="updateJoints()">
|
| 806 |
+
<span class="val-display" id="joint_0_val">-1.57</span>
|
| 807 |
</div>
|
| 808 |
<div class="slider-row">
|
| 809 |
<label>J2</label>
|
| 810 |
+
<input type="range" id="joint_1" min="-6.28" max="6.28" step="0.01" value="-1.5708" oninput="updateJoints()">
|
| 811 |
+
<span class="val-display" id="joint_1_val">-1.57</span>
|
| 812 |
</div>
|
| 813 |
<div class="slider-row">
|
| 814 |
<label>J3</label>
|
| 815 |
+
<input type="range" id="joint_2" min="-3.14" max="3.14" step="0.01" value="1.5708" oninput="updateJoints()">
|
| 816 |
+
<span class="val-display" id="joint_2_val">1.57</span>
|
| 817 |
</div>
|
| 818 |
<div class="slider-row">
|
| 819 |
<label>J4</label>
|
| 820 |
+
<input type="range" id="joint_3" min="-6.28" max="6.28" step="0.01" value="-1.5708" oninput="updateJoints()">
|
| 821 |
<span class="val-display" id="joint_3_val">-1.57</span>
|
| 822 |
</div>
|
| 823 |
<div class="slider-row">
|
| 824 |
<label>J5</label>
|
| 825 |
+
<input type="range" id="joint_4" min="-6.28" max="6.28" step="0.01" value="-1.5708" oninput="updateJoints()">
|
| 826 |
<span class="val-display" id="joint_4_val">-1.57</span>
|
| 827 |
</div>
|
| 828 |
<div class="slider-row">
|
|
|
|
| 890 |
clearInterval(reconnectTimer);
|
| 891 |
reconnectTimer = null;
|
| 892 |
}
|
| 893 |
+
// Restore saved robot selection
|
| 894 |
+
const savedRobot = localStorage.getItem('novasim_robot');
|
| 895 |
+
if (savedRobot && savedRobot !== robotSelect.value) {
|
| 896 |
+
robotSelect.value = savedRobot;
|
| 897 |
+
send('switch_robot', {robot: savedRobot});
|
| 898 |
+
updateRobotUI(savedRobot);
|
| 899 |
+
}
|
| 900 |
};
|
| 901 |
|
| 902 |
ws.onclose = () => {
|
|
|
|
| 936 |
euler[0].toFixed(2) + ', ' + euler[1].toFixed(2) + ', ' + euler[2].toFixed(2);
|
| 937 |
}
|
| 938 |
|
| 939 |
+
// Gripper: 0=open, 255=closed (Robotiq 2F-85)
|
| 940 |
document.getElementById('gripper_val').innerText =
|
| 941 |
+
((255 - data.gripper) / 255 * 100).toFixed(0) + '% open';
|
| 942 |
document.getElementById('arm_step_val').innerText = data.steps;
|
| 943 |
|
| 944 |
+
// Update joint position display and sync sliders
|
| 945 |
if (data.joint_positions) {
|
| 946 |
const jp = data.joint_positions;
|
| 947 |
document.getElementById('joint_pos_display').innerText =
|
| 948 |
jp.map(j => j.toFixed(2)).join(', ');
|
| 949 |
+
// Sync joint sliders with actual positions
|
| 950 |
+
for (let i = 0; i < 6; i++) {
|
| 951 |
+
document.getElementById('joint_' + i).value = jp[i];
|
| 952 |
+
document.getElementById('joint_' + i + '_val').innerText = jp[i].toFixed(2);
|
| 953 |
+
}
|
| 954 |
+
}
|
| 955 |
+
|
| 956 |
+
// Sync IK target sliders with actual EE position
|
| 957 |
+
if (data.end_effector) {
|
| 958 |
+
const ee = data.end_effector;
|
| 959 |
+
document.getElementById('target_x').value = ee.x;
|
| 960 |
+
document.getElementById('target_x_val').innerText = ee.x.toFixed(2);
|
| 961 |
+
document.getElementById('target_y').value = ee.y;
|
| 962 |
+
document.getElementById('target_y_val').innerText = ee.y.toFixed(2);
|
| 963 |
+
document.getElementById('target_z').value = ee.z;
|
| 964 |
+
document.getElementById('target_z_val').innerText = ee.z.toFixed(2);
|
| 965 |
}
|
| 966 |
|
| 967 |
// Update control mode display
|
|
|
|
| 1055 |
function togglePanel() {
|
| 1056 |
panelCollapsed = !panelCollapsed;
|
| 1057 |
const content = document.getElementById('panel_content');
|
| 1058 |
+
const header = document.getElementById('panel_header');
|
| 1059 |
const panel = document.getElementById('control_panel');
|
| 1060 |
if (panelCollapsed) {
|
| 1061 |
content.classList.add('collapsed');
|
| 1062 |
panel.classList.add('collapsed');
|
| 1063 |
+
header.classList.add('collapsed');
|
| 1064 |
} else {
|
| 1065 |
content.classList.remove('collapsed');
|
| 1066 |
panel.classList.remove('collapsed');
|
| 1067 |
+
header.classList.remove('collapsed');
|
| 1068 |
}
|
| 1069 |
}
|
| 1070 |
|
| 1071 |
function switchRobot() {
|
| 1072 |
const robot = robotSelect.value;
|
| 1073 |
+
localStorage.setItem('novasim_robot', robot);
|
| 1074 |
send('switch_robot', {robot});
|
| 1075 |
updateRobotUI(robot);
|
| 1076 |
}
|
|
|
|
| 1151 |
}
|
| 1152 |
|
| 1153 |
function goToHome() {
|
| 1154 |
+
// UR5e home position - official MuJoCo Menagerie elbow-up pose
|
| 1155 |
+
const home = [-1.5708, -1.5708, 1.5708, -1.5708, -1.5708, 0.0];
|
| 1156 |
for (let i = 0; i < 6; i++) {
|
| 1157 |
document.getElementById('joint_' + i).value = home[i];
|
| 1158 |
document.getElementById('joint_' + i + '_val').innerText = home[i].toFixed(2);
|
robots/ur5/model/scene.xml
CHANGED
|
@@ -345,7 +345,8 @@
|
|
| 345 |
</actuator>
|
| 346 |
|
| 347 |
<keyframe>
|
| 348 |
-
<
|
| 349 |
-
|
|
|
|
| 350 |
</keyframe>
|
| 351 |
</mujoco>
|
|
|
|
| 345 |
</actuator>
|
| 346 |
|
| 347 |
<keyframe>
|
| 348 |
+
<!-- Official MuJoCo Menagerie UR5e home pose with gripper open (0=open) -->
|
| 349 |
+
<key name="home" qpos="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0 0 0 0 0 0 0 0 0 0.5 0.2 0.45 1 0 0 0"
|
| 350 |
+
ctrl="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0 0"/>
|
| 351 |
</keyframe>
|
| 352 |
</mujoco>
|
robots/ur5/ur5_env.py
CHANGED
|
@@ -32,14 +32,14 @@ class UR5Env(gym.Env):
|
|
| 32 |
"wrist_3_joint",
|
| 33 |
]
|
| 34 |
|
| 35 |
-
# Home position -
|
| 36 |
-
#
|
| 37 |
DEFAULT_HOME_POSE = np.array([
|
| 38 |
-
|
| 39 |
-
-
|
| 40 |
-
|
| 41 |
-
-1.
|
| 42 |
-
-1.
|
| 43 |
0.0, # wrist_3 - no rotation
|
| 44 |
], dtype=np.float32)
|
| 45 |
|
|
@@ -117,8 +117,8 @@ class UR5Env(gym.Env):
|
|
| 117 |
self._target_euler = np.array([0.0, np.pi/2, 0.0], dtype=np.float32)
|
| 118 |
# Whether to use orientation in IK (user can toggle this)
|
| 119 |
self._use_orientation = True
|
| 120 |
-
# Gripper target
|
| 121 |
-
self._gripper_target =
|
| 122 |
|
| 123 |
# Control mode: 'ik' (end-effector target) or 'joint' (direct joint positions)
|
| 124 |
self._control_mode = 'ik'
|
|
@@ -152,7 +152,7 @@ class UR5Env(gym.Env):
|
|
| 152 |
return self._use_orientation
|
| 153 |
|
| 154 |
def set_gripper(self, value: float):
|
| 155 |
-
"""Set gripper target
|
| 156 |
self._gripper_target = np.clip(value, 0, 255)
|
| 157 |
|
| 158 |
def get_gripper(self):
|
|
@@ -243,7 +243,7 @@ class UR5Env(gym.Env):
|
|
| 243 |
# Set to home pose
|
| 244 |
self.data.qpos[:6] = self.DEFAULT_HOME_POSE.copy()
|
| 245 |
self.data.ctrl[:6] = self.DEFAULT_HOME_POSE.copy()
|
| 246 |
-
self.data.ctrl[6] =
|
| 247 |
|
| 248 |
# Reset box position
|
| 249 |
box_qpos_start = 6 + 8 # 6 arm joints + 8 gripper joints
|
|
@@ -254,7 +254,7 @@ class UR5Env(gym.Env):
|
|
| 254 |
self._target_pos = np.array([0.4, 0.0, 0.4], dtype=np.float32)
|
| 255 |
self._target_euler = np.array([0.0, np.pi/2, 0.0], dtype=np.float32) # Gripper pointing down
|
| 256 |
self.data.mocap_pos[0] = self._target_pos
|
| 257 |
-
self._gripper_target =
|
| 258 |
|
| 259 |
mujoco.mj_forward(self.model, self.data)
|
| 260 |
|
|
|
|
| 32 |
"wrist_3_joint",
|
| 33 |
]
|
| 34 |
|
| 35 |
+
# Home position - official MuJoCo Menagerie UR5e configuration
|
| 36 |
+
# Classic "elbow up" manipulation pose from Universal Robots
|
| 37 |
DEFAULT_HOME_POSE = np.array([
|
| 38 |
+
-1.5708, # shoulder_pan - rotated -90°
|
| 39 |
+
-1.5708, # shoulder_lift - rotated -90°
|
| 40 |
+
1.5708, # elbow - rotated +90°
|
| 41 |
+
-1.5708, # wrist_1 - rotated -90°
|
| 42 |
+
-1.5708, # wrist_2 - rotated -90°
|
| 43 |
0.0, # wrist_3 - no rotation
|
| 44 |
], dtype=np.float32)
|
| 45 |
|
|
|
|
| 117 |
self._target_euler = np.array([0.0, np.pi/2, 0.0], dtype=np.float32)
|
| 118 |
# Whether to use orientation in IK (user can toggle this)
|
| 119 |
self._use_orientation = True
|
| 120 |
+
# Gripper target: Robotiq 2F-85 uses 0=open, 255=closed
|
| 121 |
+
self._gripper_target = 0.0 # Start open
|
| 122 |
|
| 123 |
# Control mode: 'ik' (end-effector target) or 'joint' (direct joint positions)
|
| 124 |
self._control_mode = 'ik'
|
|
|
|
| 152 |
return self._use_orientation
|
| 153 |
|
| 154 |
def set_gripper(self, value: float):
|
| 155 |
+
"""Set gripper target. Robotiq 2F-85: 0=open, 255=closed."""
|
| 156 |
self._gripper_target = np.clip(value, 0, 255)
|
| 157 |
|
| 158 |
def get_gripper(self):
|
|
|
|
| 243 |
# Set to home pose
|
| 244 |
self.data.qpos[:6] = self.DEFAULT_HOME_POSE.copy()
|
| 245 |
self.data.ctrl[:6] = self.DEFAULT_HOME_POSE.copy()
|
| 246 |
+
self.data.ctrl[6] = 0 # Gripper open (Robotiq: 0=open, 255=closed)
|
| 247 |
|
| 248 |
# Reset box position
|
| 249 |
box_qpos_start = 6 + 8 # 6 arm joints + 8 gripper joints
|
|
|
|
| 254 |
self._target_pos = np.array([0.4, 0.0, 0.4], dtype=np.float32)
|
| 255 |
self._target_euler = np.array([0.0, np.pi/2, 0.0], dtype=np.float32) # Gripper pointing down
|
| 256 |
self.data.mocap_pos[0] = self._target_pos
|
| 257 |
+
self._gripper_target = 0.0 # Open gripper
|
| 258 |
|
| 259 |
mujoco.mj_forward(self.model, self.data)
|
| 260 |
|