| @@ -1,40 +1,235 @@ | |||
| # dora-franka-mujoco | |||
| ## Getting started | |||
| A MuJoCo-based Franka Emika Panda robot simulation node for the Dora dataflow framework. This node provides high-fidelity physics simulation with real-time control capabilities, supporting both gamepad and programmatic control interfaces. | |||
| - Install it with uv: | |||
| ## Features | |||
| - **High-Fidelity Simulation**: Physics-based simulation using MuJoCo with detailed Franka Panda model | |||
| - **Dual Control Modes**: Support for both gamepad control and target pose commands | |||
| - **Cartesian Control**: End-effector position and orientation control with nullspace joint control | |||
| - **Real-time Feedback**: Joint positions and end-effector position streaming | |||
| - **Automatic Mesh Management**: Automatic download of required mesh files from Hugging Face | |||
| - **Interactive Visualization**: Built-in MuJoCo viewer for real-time monitoring | |||
| ## Robot Model | |||
| - **Robot**: Franka Emika Panda (7-DOF arm + 2-DOF gripper) | |||
| - **Environment**: Table workspace with movable objects | |||
| - **Physics**: Full dynamics simulation with gravity and collision detection | |||
| - **Control**: Position control with damped least squares inverse kinematics | |||
| ## Getting Started | |||
| ### Installation | |||
| ```bash | |||
| # Create virtual environment | |||
| uv venv -p 3.11 --seed | |||
| # Install the package | |||
| uv pip install -e . | |||
| ``` | |||
| ## Contribution Guide | |||
| - Format with [ruff](https://docs.astral.sh/ruff/): | |||
| ### Quick Start | |||
| 1. **Run with gamepad control**: | |||
| ```bash | |||
| uv pip install ruff | |||
| uv run ruff check . --fix | |||
| dora build demo.yml | |||
| # run the node | |||
| dora run demo.yml | |||
| ``` | |||
| - Lint with ruff: | |||
| 2. **Connect a gamepad** (Xbox/PlayStation controller) and use the controls below | |||
| ```bash | |||
| uv run ruff check . | |||
| ### Controls | |||
| #### Gamepad Mapping | |||
| - **Left Stick X**: Move along X-axis | |||
| - **Left Stick Y**: Move along Y-axis | |||
| - **Right Stick Y**: Move along Z-axis | |||
| - **LB/RB**: Decrease/Increase movement speed | |||
| - **START**: Reset robot to home position | |||
| - **X Button**: Close gripper | |||
| - **Y Button**: Open gripper | |||
| #### Programmatic Control | |||
| Send target poses as `[x, y, z, roll, pitch, yaw]` arrays to the `target_pose` input. | |||
| ## YAML Specification | |||
| ### Node Configuration | |||
| ```yaml | |||
| nodes: | |||
| - id: mujoco_franka | |||
| build: pip install -e . | |||
| path: dora-franka-mujoco | |||
| inputs: | |||
| raw_control: gamepad/raw_control # Gamepad input (optional) | |||
| target_pose: controller/target_pose # Target pose commands (optional) | |||
| tick: dora/timer/millis/10 # Simulation tick rate | |||
| outputs: | |||
| - joint_positions # 7-DOF joint angles | |||
| - ee_position # End-effector position [x, y, z] | |||
| ``` | |||
| - Test with [pytest](https://github.com/pytest-dev/pytest) | |||
| ### Input Specifications | |||
| | Input | Type | Description | Format | | |||
| |-------|------|-------------|---------| | |||
| | `raw_control` | `pa.string()` | Gamepad input (handled by gamepad node) | `{"axes": [float], "buttons": [bool]}` | | |||
| | `target_pose` | `pa.array(float64)` | Target pose command | `[x, y, z, roll, pitch, yaw]` (position in meters, orientation in degrees) | | |||
| | `tick` | Timer | Simulation step trigger | Timer event | | |||
| ### Output Specifications | |||
| | Output | Type | Description | Metadata | | |||
| |--------|------|-------------|----------| | |||
| | `joint_positions` | `pa.array(float64)` | 7-DOF joint angles (radians) | `{"type": "joint_positions"}` | | |||
| | `ee_position` | `pa.array(float64)` | End-effector position [x, y, z] (meters) | `{"type": "ee_position"}` | | |||
| ## Examples | |||
| ### Basic Simulation | |||
| ```yaml | |||
| # Minimal setup for physics simulation | |||
| nodes: | |||
| - id: mujoco_franka | |||
| build: pip install -e . | |||
| path: dora-franka-mujoco | |||
| inputs: | |||
| tick: dora/timer/millis/10 | |||
| outputs: | |||
| - joint_positions | |||
| - ee_position | |||
| ``` | |||
| ### Gamepad Control | |||
| ```yaml | |||
| # Full gamepad control setup | |||
| nodes: | |||
| - id: gamepad | |||
| build: pip install -e ../gamepad | |||
| path: gamepad | |||
| outputs: | |||
| - raw_control | |||
| inputs: | |||
| tick: dora/timer/millis/10 | |||
| - id: mujoco_franka | |||
| build: pip install -e . | |||
| path: dora-franka-mujoco | |||
| inputs: | |||
| raw_control: gamepad/raw_control | |||
| tick: dora/timer/millis/10 | |||
| outputs: | |||
| - joint_positions | |||
| - ee_position | |||
| ``` | |||
| ### Programmatic Control | |||
| ```python | |||
| # Send target pose commands | |||
| import pyarrow as pa | |||
| from dora import Node | |||
| node = Node() | |||
| # Move to position (0.5, 0.2, 0.6) with downward orientation | |||
| target_pose = [0.5, 0.2, 0.6, 180.0, 0.0, 90.0] # x, y, z, roll, pitch, yaw | |||
| node.send_output( | |||
| "target_pose", | |||
| pa.array(target_pose, type=pa.float64()), | |||
| metadata={"timestamp": time.time()} | |||
| ) | |||
| ``` | |||
| ## Technical Details | |||
| ### Control System | |||
| - **Inverse Kinematics**: Damped least squares with nullspace control | |||
| - **Target Orientation**: Default downward-facing gripper (configurable) | |||
| - **Joint Limits**: Enforced according to Franka specifications | |||
| - **Velocity Limits**: Maximum 0.785 rad/s per joint | |||
| ### Mesh Files | |||
| The node automatically downloads required mesh files from Hugging Face Hub: | |||
| - **Repository**: `SGPatil/Mujoco_franka_meshes` | |||
| - **Cache Location**: `~/.cache/dora-mujoco-franka/meshes/` | |||
| - **File Types**: STL and OBJ mesh files for visual and collision geometry | |||
| ### Simulation Parameters | |||
| - **Timestep**: 0.002s (500Hz physics simulation) | |||
| - **Integration**: 0.1s control integration time | |||
| - **Damping**: 1e-4 for numerical stability | |||
| - **Position Gains**: Kpos=0.95, Kori=0.95 | |||
| - **Nullspace Gains**: [10, 10, 10, 10, 5, 5, 5] | |||
| ## Troubleshooting | |||
| ### Common Issues | |||
| 1. **Mesh files not downloading**: | |||
| ``` | |||
| Error downloading mesh files: [error details] | |||
| ``` | |||
| - Check internet connection | |||
| - Verify Hugging Face Hub access | |||
| - Clear cache: `rm -rf ~/.cache/dora-mujoco-franka/` | |||
| 2. **Gamepad not detected**: | |||
| - Ensure gamepad is connected and recognized by OS | |||
| - Test with `js_test` on Linux or similar tools | |||
| - Check gamepad node configuration | |||
| 3. **Robot not responding to commands**: | |||
| - Verify input connections in YAML | |||
| - Check that timer is triggering simulation steps | |||
| - Use MuJoCo viewer to monitor robot state | |||
| 4. **Simulation running slowly**: | |||
| - Reduce timer frequency (increase interval) | |||
| - Close other applications using GPU/CPU | |||
| - Consider headless mode for better performance | |||
| ## Development | |||
| ### Code Quality | |||
| ```bash | |||
| # Format code | |||
| uv run ruff check . --fix | |||
| # Lint code | |||
| uv run ruff check . | |||
| # Run tests | |||
| uv pip install pytest | |||
| uv run pytest . # Test | |||
| uv run pytest . | |||
| ``` | |||
| ## YAML Specification | |||
| ### Adding New Features | |||
| 1. Modify the `RobotController` class for new control modes | |||
| 2. Update input/output specifications | |||
| 3. Add corresponding tests | |||
| 4. Update documentation | |||
| ## Examples | |||
| ## Contributing | |||
| Contributions are welcome! Please: | |||
| 1. Follow the existing code style (ruff formatting) | |||
| 2. Add tests for new features | |||
| 3. Update documentation as needed | |||
| 4. Submit pull requests with clear descriptions | |||
| ## License | |||
| dora-franka-mujoco's code are released under the MIT License | |||
| This project is released under the MIT License. See the LICENSE file for details. | |||
| ## Related Projects | |||
| - [Dora-rs](https://github.com/dora-rs/dora) - The dataflow framework | |||
| - [MuJoCo](https://github.com/google-deepmind/mujoco) - Physics simulation engine | |||
| - [Franka Control Interface](https://frankaemika.github.io/docs/) - Official Franka documentation | |||
| @@ -5,7 +5,7 @@ readme_path = os.path.join(os.path.dirname(os.path.dirname(__file__)), "README.m | |||
| # Read the content of the README file | |||
| try: | |||
| with open(readme_path, "r", encoding="utf-8") as f: | |||
| with open(readme_path, encoding="utf-8") as f: | |||
| __doc__ = f.read() | |||
| except FileNotFoundError: | |||
| __doc__ = "README file not found." | |||
| @@ -65,4 +65,3 @@ link7_5.obj | |||
| link7_6.obj | |||
| link7_7.obj | |||
| link7.stl | |||
| names.txt | |||
| @@ -8,11 +8,9 @@ def get_required_mesh_files(): | |||
| """Get list of required mesh files from names.txt""" | |||
| names_file = Path(__file__).parent / "franka_emika_panda" / "assets" / "names.txt" | |||
| with open(names_file, 'r') as f: | |||
| mesh_files = [line.strip() for line in f if line.strip() and (line.strip().endswith('.stl') or line.strip().endswith('.obj'))] | |||
| with open(names_file) as f: | |||
| return [line.strip() for line in f if line.strip() and (line.strip().endswith('.stl') or line.strip().endswith('.obj'))] | |||
| return mesh_files | |||
| MESH_FILES = get_required_mesh_files() | |||
| REPO_ID = "SGPatil/Mujoco_franka_meshes" | |||
| REPO_TYPE = "dataset" | |||
| @@ -26,5 +26,4 @@ extend-select = [ | |||
| "RET", # Ruff's RET rule | |||
| "RSE", # Ruff's RSE rule | |||
| "NPY", # Ruff's NPY rule | |||
| "N", # Ruff's N rule | |||
| ] | |||
| @@ -0,0 +1,187 @@ | |||
| # dora-mujoco-sim | |||
| A MuJoCo physics simulation node for the Dora dataflow framework. This node provides real-time physics simulation with support for a wide range of robots from the `robot_descriptions` package, as well as custom robot models. | |||
| ## Features | |||
| - **Wide Robot Support**: Built-in support for 50+ robot models including quadrupeds, humanoids, arms, drones, and more | |||
| - **Flexible Model Loading**: Load robots by name (via robot_descriptions) or direct XML file paths | |||
| - **Real-time Simulation**: Continuous physics simulation with configurable tick rates | |||
| - **Live Visualization**: Optional MuJoCo viewer for real-time 3D visualization | |||
| - **Rich Data Output**: Joint positions, velocities, accelerations, and sensor data | |||
| ## Supported Robot Categories | |||
| | Category | Examples | | |||
| |----------|----------| | |||
| | **Quadrupeds** | Unitree Go1/Go2/A1, ANYmal B/C, Boston Dynamics Spot | | |||
| | **Humanoids** | Unitree G1/H1, Apptronik Apollo, TALOS, JVRC-1 | | |||
| | **Arms** | Franka Panda, KUKA iiwa14, Universal Robots UR5e/UR10e | | |||
| | **Dual Arms** | Aloha 2, Baxter, YuMi | | |||
| | **End Effectors** | Allegro Hand, Shadow Hand, Robotiq 2F-85 | | |||
| | **Drones** | Crazyflie 2.0, Skydio X2 | | |||
| | **Educational** | Double Pendulum | | |||
| ## Getting Started | |||
| ### Quick Start | |||
| 1. **Run a simple simulation**: | |||
| ```bash | |||
| dora build demo.yml | |||
| # Start with Unitree Go2 quadruped | |||
| dora run demo.yml | |||
| ``` | |||
| 2. **Use different robots**: | |||
| ```python | |||
| # In main.py, modify the model name (line ~95) | |||
| model_path_or_name = "franka_panda" # Change this line | |||
| # Examples: "go2", "franka_panda", "g1", "spot", etc. | |||
| ``` | |||
| 3. **Use custom robot models**: | |||
| ```python | |||
| # In main.py, use file path instead of model name | |||
| model_path_or_name = "/path/to/my_robot/scene.xml" | |||
| ``` | |||
| ## Usage Examples | |||
| TODO | |||
| ### Available Robot Models | |||
| The simulator supports all models from the `robot_descriptions` package. Common names include: | |||
| - **Quadrupeds**: `go1`, `go2`, `a1`, `aliengo`, `anymal_b`, `anymal_c`, `spot` | |||
| - **Humanoids**: `g1`, `h1`, `apollo`, `talos`, `jvrc`, `cassie` | |||
| - **Arms**: `franka_panda`, `ur5e`, `ur10e`, `iiwa14`, `gen3`, `sawyer` | |||
| - **Hands**: `allegro_hand`, `shadow_hand`, `leap_hand`, `robotiq_2f85` | |||
| See [`robot_models.json`](dora_mujoco_sim/robot_models.json) for the complete list. | |||
| ## YAML Specification | |||
| ### Node Configuration | |||
| ```yaml | |||
| nodes: | |||
| - id: mujoco_sim | |||
| build: pip install -e . | |||
| path: dora-mujoco-sim | |||
| env: | |||
| MODEL_NAME: "go2" # Robot model name or file path | |||
| inputs: | |||
| TICK: dora/timer/millis/2 # Simulation tick rate (500Hz) | |||
| outputs: | |||
| - joint_positions # Joint position array | |||
| - joint_velocities # Joint velocity array | |||
| - sensor_data # Sensor readings array | |||
| ``` | |||
| ### Input Specification | |||
| - **TICK**: Timer events that trigger simulation steps and data output | |||
| - Format: `dora/timer/millis/<interval>` | |||
| - Example: `dora/timer/millis/1` for 1000Hz updates | |||
| ### Output Specification | |||
| | Output | Type | Description | Metadata | | |||
| |--------|------|-------------|----------| | |||
| | `joint_positions` | `pa.array(float64)` | Joint positions (qpos) | `timestamp` | | |||
| | `joint_velocities` | `pa.array(float64)` | Joint velocities (qvel) | `timestamp` | | |||
| | `sensor_data` | `pa.array(float64)` | Sensor readings (yet to manage sensors, currently dumping raw output) | `timestamp` | | |||
| ## Architecture | |||
| ``` | |||
| ┌─────────────────┐ TICK ┌─────────────────┐ | |||
| │ Dora Timer │───────────▶│ MuJoCo Node │ | |||
| └─────────────────┘ │ │ | |||
| │ ┌─────────────┐ │ joint_positions | |||
| │ │ Simulator │ │──────────────────▶ | |||
| │ │ │ │ joint_velocities | |||
| │ │ ┌────────┐ │ │──────────────────▶ | |||
| │ │ │Renderer│ │ │ sensor_data | |||
| │ │ └────────┘ │ │──────────────────▶ | |||
| │ │ │ │ | |||
| │ └─────────────┘ | | |||
| └─────────────────┘ | |||
| ``` | |||
| ## Development | |||
| ### Code Quality | |||
| ```bash | |||
| # Format code | |||
| uv run ruff check . --fix | |||
| # Lint code | |||
| uv run ruff check . | |||
| # Run tests | |||
| uv pip install pytest | |||
| uv run pytest . | |||
| ``` | |||
| ### Adding New Models | |||
| To add support for new robot models: | |||
| 1. Add the model mapping to [`robot_models.json`](dora_mujoco_sim/robot_models.json): | |||
| ```json | |||
| { | |||
| "category_name": { | |||
| "my_robot": "my_robot_mj_description" | |||
| } | |||
| } | |||
| ``` | |||
| 2. Ensure the model is available in `robot_descriptions` or provide the XML file path directly. | |||
| ## Configuration | |||
| ### Simulation Parameters | |||
| - **Timestep**: Fixed at MuJoCo default (0.002s = 500Hz physics) | |||
| - **Output Rate**: Controlled by TICK input frequency | |||
| ## Troubleshooting | |||
| ### Common Issues | |||
| 1. **Model not found**: | |||
| ``` | |||
| ERROR: Model file not found for my_robot | |||
| ``` | |||
| - Check if the model name exists in `robot_models.json` | |||
| - Verify `robot_descriptions` has the model installed | |||
| - Use absolute file path for custom models | |||
| 2. **Scene variant missing**: | |||
| ``` | |||
| WARNING: Failed to load scene variant | |||
| ``` | |||
| - Normal behavior - falls back to robot-only model | |||
| - Scene variants include ground plane and lighting | |||
| 3. **Viewer issues**: | |||
| - Use `HEADLESS` for server environments | |||
| - Ensure proper OpenGL/graphics drivers | |||
| ## License | |||
| This project is released under the MIT License. See the LICENSE file for details. | |||
| ## Contributing | |||
| Contributions are welcome! Please: | |||
| 1. Follow the existing code style (ruff formatting) | |||
| 2. Add tests for new features | |||
| 3. Update documentation as needed | |||
| 4. Submit pull requests with clear descriptions | |||
| ## Related Projects | |||
| - [Dora-rs](https://github.com/dora-rs/dora) - The dataflow framework | |||
| - [MuJoCo](https://github.com/google-deepmind/mujoco) - Physics simulation engine | |||
| - [robot_descriptions](https://github.com/robot-descriptions/robot_descriptions) - Robot model collection | |||
| @@ -0,0 +1,28 @@ | |||
| nodes: | |||
| - id: mujoco_sim | |||
| build: pip install -e . | |||
| path: dora-mujoco-sim | |||
| inputs: | |||
| tick: dora/timer/millis/2 # 500 Hz data collection | |||
| # control_input: controller/output | |||
| # render_request: visualizer/request | |||
| # change_model: config/model_change | |||
| outputs: | |||
| - joint_positions | |||
| - joint_velocities | |||
| - sensor_data | |||
| - rendered_frame | |||
| # - id: controller | |||
| # # Your control logic node | |||
| # inputs: | |||
| # joint_positions: mujoco_sim/joint_positions | |||
| # outputs: | |||
| # - output | |||
| # - id: data_collector | |||
| # # Your data collection node | |||
| # inputs: | |||
| # joint_positions: mujoco_sim/joint_positions | |||
| # joint_velocities: mujoco_sim/joint_velocities | |||
| # sensor_data: mujoco_sim/sensor_data | |||
| @@ -0,0 +1,13 @@ | |||
| """TODO: Add docstring.""" | |||
| import os | |||
| # Define the path to the README file relative to the package directory | |||
| readme_path = os.path.join(os.path.dirname(os.path.dirname(__file__)), "README.md") | |||
| # Read the content of the README file | |||
| try: | |||
| with open(readme_path, encoding="utf-8") as f: | |||
| __doc__ = f.read() | |||
| except FileNotFoundError: | |||
| __doc__ = "README file not found." | |||
| @@ -0,0 +1,6 @@ | |||
| """TODO: Add docstring.""" | |||
| from .main import main | |||
| if __name__ == "__main__": | |||
| main() | |||
| @@ -0,0 +1,154 @@ | |||
| """MuJoCo simulation node for Dora with robot descriptions support.""" | |||
| import numpy as np | |||
| import pyarrow as pa | |||
| import mujoco | |||
| import mujoco.viewer | |||
| from dora import Node | |||
| import json | |||
| from pathlib import Path | |||
| import time | |||
| from typing import Dict, Any | |||
| from robot_descriptions.loaders.mujoco import load_robot_description | |||
| class MuJoCoSimulator: | |||
| """MuJoCo simulator for Dora.""" | |||
| def __init__(self, model_path_or_name: str = "go2"): | |||
| """Initialize the MuJoCo simulator.""" | |||
| self.model_path_or_name = model_path_or_name | |||
| self.model = None | |||
| self.data = None | |||
| self.viewer = None | |||
| self.state_data = {} | |||
| self.model_mapping = self._load_model_mapping() | |||
| def _load_model_mapping(self) -> dict: | |||
| """Load robot model mapping from JSON file.""" | |||
| config_path = Path(__file__).parent / "robot_models.json" | |||
| with open(config_path) as f: | |||
| mapping_data = json.load(f) | |||
| model_mapping = {} | |||
| for models in mapping_data.values(): | |||
| model_mapping.update(models) | |||
| return model_mapping | |||
| def load_model(self) -> bool: | |||
| """Load MuJoCo model from path or robot description name.""" | |||
| model_path = Path(self.model_path_or_name) | |||
| if model_path.exists() and model_path.suffix == '.xml': | |||
| # print(f"Loading model from direct path: {model_path}") | |||
| self.model = mujoco.MjModel.from_xml_path(str(model_path)) | |||
| else: | |||
| # Treat as model name - robot_descriptions | |||
| description_name = self.model_mapping.get( | |||
| self.model_path_or_name, | |||
| f"{self.model_path_or_name}_mj_description" | |||
| ) | |||
| self.model = load_robot_description(description_name, variant="scene") | |||
| # Initialize simulation data | |||
| self.data = mujoco.MjData(self.model) | |||
| # Set control to neutral position | |||
| if self.model.nkey > 0: | |||
| mujoco.mj_resetDataKeyframe(self.model, self.data, 0) | |||
| else: | |||
| mujoco.mj_resetData(self.model, self.data) | |||
| # Initialize state data | |||
| self._update_state_data() | |||
| return True | |||
| def step_simulation(self): | |||
| """Step the simulation forward.""" | |||
| mujoco.mj_step(self.model, self.data) | |||
| self._update_state_data() | |||
| def _update_state_data(self): | |||
| """Update state data that can be sent via Dora.""" | |||
| self.state_data = { | |||
| "time": self.data.time, # Current simulation time | |||
| "qpos": self.data.qpos.copy(), # Joint positions | |||
| "qvel": self.data.qvel.copy(), # Joint velocities | |||
| "qacc": self.data.qacc.copy(), # Joint accelerations | |||
| "ctrl": self.data.ctrl.copy(), # Control inputs/actuator commands | |||
| "qfrc_applied": self.data.qfrc_applied.copy(), # External forces applied to joints | |||
| "sensordata": self.data.sensordata.copy() if self.model.nsensor > 0 else np.array([]) # Sensor readings | |||
| } | |||
| def get_state(self) -> Dict[str, Any]: | |||
| """Get current simulation state.""" | |||
| return self.state_data.copy() | |||
| def main(): | |||
| """Run the main Dora node function.""" | |||
| node = Node() | |||
| # Configuration - can be either a model name or direct path | |||
| model_path_or_name = "go2" # Examples: "go2", "franka_panda", "/path/to/scene.xml" | |||
| # Initialize simulator | |||
| simulator = MuJoCoSimulator(model_path_or_name) | |||
| # Load model | |||
| if not simulator.load_model(): | |||
| print("Failed to load MuJoCo model") | |||
| return | |||
| print("MuJoCo simulation node started") | |||
| # Launch viewer (optional - comment out for headless) | |||
| with mujoco.viewer.launch_passive(simulator.model, simulator.data) as viewer: | |||
| print("Viewer launched") | |||
| # Main Dora event loop | |||
| for event in node: | |||
| # Always step simulation | |||
| simulator.step_simulation() | |||
| viewer.sync() | |||
| if event["type"] == "INPUT": | |||
| state = simulator.get_state() | |||
| # Get current time | |||
| current_time = state.get("time", time.time()) | |||
| # Send joint positions | |||
| if "qpos" in state: | |||
| print(f"Sending joint positions: {state['qpos']}") | |||
| node.send_output( | |||
| "joint_positions", | |||
| pa.array(state["qpos"]), | |||
| {"timestamp": current_time} | |||
| ) | |||
| # Send joint velocities | |||
| if "qvel" in state: | |||
| node.send_output( | |||
| "joint_velocities", | |||
| pa.array(state["qvel"]), | |||
| {"timestamp": current_time} | |||
| ) | |||
| # Send sensor data if available | |||
| if "sensordata" in state and len(state["sensordata"]) > 0: | |||
| node.send_output( | |||
| "sensor_data", | |||
| pa.array(state["sensordata"]), | |||
| {"timestamp": current_time} | |||
| ) | |||
| if __name__ == "__main__": | |||
| main() | |||
| @@ -0,0 +1,62 @@ | |||
| { | |||
| "arms": { | |||
| "arx_l5": "arx_l5_mj_description", | |||
| "fr3": "fr3_mj_description", | |||
| "franka_panda": "panda_mj_description", | |||
| "panda": "panda_mj_description", | |||
| "gen3": "gen3_mj_description", | |||
| "iiwa14": "iiwa14_mj_description", | |||
| "kuka_iiwa14": "iiwa14_mj_description", | |||
| "piper": "piper_mj_description", | |||
| "sawyer": "sawyer_mj_description", | |||
| "so_arm100": "so_arm100_mj_description", | |||
| "ur10e": "ur10e_mj_description", | |||
| "ur5e": "ur5e_mj_description", | |||
| "viper": "viper_mj_description", | |||
| "widow": "widow_mj_description", | |||
| "xarm7": "xarm7_mj_description", | |||
| "yam": "yam_mj_description", | |||
| "z1": "z1_mj_description", | |||
| "low_cost_robot_arm": "low_cost_robot_arm_mj_description" | |||
| }, | |||
| "bipeds": { | |||
| "cassie": "cassie_mj_description" | |||
| }, | |||
| "dual_arms": { | |||
| "aloha": "aloha_mj_description", | |||
| "aloha_2": "aloha_mj_description" | |||
| }, | |||
| "drones": { | |||
| "crazyflie_2": "cf2_mj_description", | |||
| "cf2": "cf2_mj_description", | |||
| "skydio_x2": "skydio_x2_mj_description" | |||
| }, | |||
| "end_effectors": { | |||
| "ability_hand": "ability_hand_mj_description", | |||
| "allegro_hand": "allegro_hand_mj_description", | |||
| "leap_hand": "leap_hand_mj_description", | |||
| "robotiq_2f85": "robotiq_2f85_mj_description", | |||
| "robotiq_2f85_v4": "robotiq_2f85_v4_mj_description", | |||
| "shadow_dexee": "shadow_dexee_mj_description", | |||
| "shadow_hand": "shadow_hand_mj_description" | |||
| }, | |||
| "humanoids": { | |||
| "apollo": "apollo_mj_description", | |||
| "adam_lite": "adam_lite_mj_description", | |||
| "elf2": "elf2_mj_description", | |||
| "g1": "g1_mj_description", | |||
| "h1": "h1_mj_description", | |||
| "jvrc": "jvrc_mj_description", | |||
| "op3": "op3_mj_description", | |||
| "talos": "talos_mj_description" | |||
| }, | |||
| "quadrupeds": { | |||
| "a1": "a1_mj_description", | |||
| "aliengo": "aliengo_mj_description", | |||
| "anymal_b": "anymal_b_mj_description", | |||
| "anymal_c": "anymal_c_mj_description", | |||
| "go1": "go1_mj_description", | |||
| "go2": "go2_mj_description", | |||
| "spot": "spot_mj_description" | |||
| } | |||
| } | |||
| @@ -0,0 +1,33 @@ | |||
| [project] | |||
| name = "dora-mujoco-sim" | |||
| version = "0.1.0" | |||
| authors = [{ name = "Your Name", email = "email@email.com" }] | |||
| description = "MuJoCo simulation node for Dora" | |||
| license = { text = "MIT" } | |||
| readme = "README.md" | |||
| requires-python = ">=3.8" | |||
| dependencies = [ | |||
| "dora-rs >= 0.3.9", | |||
| "mujoco >= 3.1.6", | |||
| "numpy >= 1.21.0", | |||
| "pyarrow >= 14.0.1", | |||
| "robot_descriptions >= 1.12.0", | |||
| ] | |||
| [dependency-groups] | |||
| dev = ["pytest >=8.1.1", "ruff >=0.9.1"] | |||
| [project.scripts] | |||
| dora-mujoco-sim = "dora_mujoco_sim.main:main" | |||
| [tool.ruff.lint] | |||
| extend-select = [ | |||
| "D", # pydocstyle | |||
| "UP", # pyupgrade | |||
| "PERF", # Ruff's PERF rule | |||
| "RET", # Ruff's RET rule | |||
| "RSE", # Ruff's RSE rule | |||
| "NPY", # Ruff's NPY rule | |||
| "N", # Ruff's N rule | |||
| ] | |||
| @@ -0,0 +1,13 @@ | |||
| """Test module for dora_mujoco_sim package.""" | |||
| import pytest | |||
| def test_import_main(): | |||
| """Test importing and running the main function.""" | |||
| from dora_mujoco_sim.main import main | |||
| # Check that everything is working, and catch Dora RuntimeError | |||
| # as we're not running in a Dora dataflow. | |||
| with pytest.raises(RuntimeError): | |||
| main() | |||