Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,3 +2,4 @@ build/
install/
log/
.vscode/
MUJOCO_LOG.TXT
30 changes: 30 additions & 0 deletions CLAUDE.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
# AI Code Assistant Instructions for MoveIt Pro Example Workspace

## MuJoCo Scene Files

### Keyframe qpos must match model DOF count

When editing `scene.xml` files (adding/removing bodies with joints), the `<keyframe>` section's `qpos` attribute must have exactly the number of values matching the model's total degrees of freedom. A mismatch causes `ros2_control_node` to crash with:

```
Error: keyframe 0: invalid qpos size, expected length <N>
```

Each joint type contributes to qpos:
- **freejoint**: 7 values (x, y, z, qw, qx, qy, qz)
- **hinge/slide**: 1 value each
- **ball**: 4 values (quaternion)

After adding or removing bodies with joints, either:
1. **Remove the keyframe** and let MuJoCo use body `pos=` attributes for initial positions
2. **Regenerate the keyframe** from the MuJoCo Interactive Viewer (Ctrl+Shift+K) once the scene is stable

### MuJoCo documentation

Refer to [docs.picknik.ai](https://docs.picknik.ai) for MuJoCo configuration guides:

- [Physics Simulator Setup](https://docs.picknik.ai/how_to/configuration_tutorials/migrate_to_mujoco_config/) — creating scene.xml from URDF, camera/sensor setup, mesh conversion, MuJoCo Interactive Viewer
- [config.yaml Reference](https://docs.picknik.ai/how_to/configuration_tutorials/config_yaml_reference/) — `hardware` section for `picknik_mujoco_ros/MujocoSystem` plugin configuration
- [Simulator Keyframes Setup](https://docs.picknik.ai/how_to/configuration_tutorials/configure_keyframes/) — defining keyframes in scene.xml, `ResetMujocoKeyframe` Behavior
- [Optimize Model Meshes](https://docs.picknik.ai/how_to/configuration_tutorials/optimizing_robot_model_meshes/) — MuJoCo enforces 1-200,000 faces per STL
- [Simulation Troubleshooting](https://docs.picknik.ai/troubleshooting/Simulation%20Troubleshooting/) — physics parameters, grip stability, mass/inertia errors, rendering issues
11 changes: 9 additions & 2 deletions src/lab_sim/config/control/picknik_ur.ros2_control.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -64,18 +64,25 @@ joint_trajectory_controller:
stopped_velocity_tolerance: 0.0
goal_time: 0.0
linear_rail_joint:
trajectory: 0.5
goal: 0.05
shoulder_pan_joint:
trajectory: 0.5
goal: 0.05
shoulder_lift_joint:
trajectory: 0.5
goal: 0.05
elbow_joint:
trajectory: 0.5
goal: 0.05
wrist_1_joint:
trajectory: 0.5
goal: 0.05
wrist_2_joint:
trajectory: 0.5
goal: 0.05
wrist_3_joint:
trajectory: 0.5
goal: 0.05
acceleration_limits:
linear_rail_joint: 10.0
Expand All @@ -91,8 +98,8 @@ robotiq_gripper_controller:
default: true
joint: robotiq_85_left_knuckle_joint
allow_stalling: true
stall_timeout: 0.05
goal_tolerance: 0.02
stall_timeout: 0.3
goal_tolerance: 0.3

force_torque_sensor_broadcaster:
ros__parameters:
Expand Down
3 changes: 3 additions & 0 deletions src/lab_sim/description/keyboard-texture.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
3 changes: 3 additions & 0 deletions src/lab_sim/description/laptop-screen.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
12 changes: 6 additions & 6 deletions src/lab_sim/description/picknik_ur.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -663,7 +663,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size="5.0 0.6 0.30" />
<box size="5.0 0.2 0.30" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand All @@ -672,7 +672,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0.14 0.125" />
<geometry>
<box size="5.0 0.2 0.5" />
<box size="5.0 0.12 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand All @@ -681,7 +681,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 -0.22 0.125" />
<geometry>
<box size="5.0 0.12 0.5" />
<box size="5.0 0.08 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand All @@ -690,7 +690,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0 0" />
<geometry>
<box size="5.0 0.6 0.3" />
<box size="5.0 0.2 0.3" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand All @@ -699,7 +699,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 0.14 0.125" />
<geometry>
<box size="5.0 0.2 0.5" />
<box size="5.0 0.12 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand All @@ -708,7 +708,7 @@
<collision>
<origin rpy="0 0 0" xyz="0 -0.22 0.125" />
<geometry>
<box size="5.0 0.12 0.5" />
<box size="5.0 0.08 0.5" />
</geometry>
<material name="grey">
<color rgba="0.1 0.1 0.1 1.0" />
Expand Down
Loading
Loading