ARIEL Lynx Arm¶

How does the ARIEL Lynx Arm module work?¶

This module handles the physical simulation of the Lynx robot arm using the MuJoCo physics engine. It provides a testing ground for robotic manipulator behavior and integration with ARIEL’s other capabilities.

In this demonstration, the environment utilizes a TableWorld scene instead of a standard flat world, presenting a more realistic workspace for a manipulator arm. A randomized controller applies continuous random actions to all robot actuators at each simulation step.

This file demonstrates the process of configuring the MuJoCo simulation, setting up camera viewpoints, controlling the actuator states with a random policy, and auto-capturing a screenshot of the simulation before it loops in the interactive viewer.

The implementation of the Lynxmotion robot arm into ARIEL is still work in progress. But this file serves as a first step into the showcase of how to work with it.

[ ]:
# Standard library
import pathlib
import sys
import time

# Third-party libraries
import imageio.v2 as imageio
import mujoco
import mujoco.viewer
import numpy as np

sys.path.append(str(pathlib.Path.cwd()))

# Local libraries
from ariel.body_phenotypes.Lynx_Arm.lynx.morphlib.scenes.table import TableWorld
from ariel.body_phenotypes.Lynx_Arm.lynx.robots.lynx_manipulator.mj_constructor import (
    construct_lynx,
)

Define the Random Controller¶

[ ]:
def random_controller(model, data) -> None:
    # Generate random actions
    # Action range: (-pi/2, pi/2)

    data.ctrl[:] = np.random.uniform(
        (-np.pi) / 2,
        (np.pi) / 2,
        size=model.nu,
    )
def sine_controller(model, data) -> None:
    # Set the amplitude to match your previous range: (-pi/2, pi/2)
    amplitude = np.pi / 2

    # Set how fast the arm moves (in Hertz)
    frequency = 1.0

    # Calculate the sine wave value based on the current simulation time
    action = amplitude * np.sin(2 * np.pi * frequency * data.time)

    # Apply the action to all actuators
    data.ctrl[:] = action

Main Simulation Runner¶

[ ]:
def run(robot, with_viewer: bool = True) -> None:
    # MuJoCo configuration
    viz_options = mujoco.MjvOption()
    viz_options.flags[mujoco.mjtVisFlag.mjVIS_TRANSPARENT] = False
    viz_options.flags[mujoco.mjtVisFlag.mjVIS_ACTUATOR] = True
    viz_options.flags[mujoco.mjtVisFlag.mjVIS_BODYBVH] = True

    # MuJoCo basics
    # world = SimpleFlatWorld()
    world = TableWorld()  # Use the table world instead of the simple flat world

    # Set transparency of all geoms:
    # [Initialization of `model` and `data` goes here]
    # print(f"DoF (model.nv): {model.nv}, Actuators (model.nu): {model.nu}")

    mujoco.set_mjcb_control(None)
    # Reset state and time of simulation
    mujoco.mj_resetData(model, data)

    # View
    mujoco.set_mjcb_control(sine_controller)
    if with_viewer:
        with mujoco.viewer.launch(model, data) as viewer:
            # Set camera
            viewer.cam.azimuth = -180
            viewer.cam.elevation = -10
            viewer.cam.distance = 2.0
            viewer.cam.lookat[:] = np.array([0.0, 0.0, 0.8])

            # ======= auto screenshot =======
            renderer = mujoco.Renderer(model)
            renderer.update_scene(data, camera=viewer.cam)
            img = renderer.render()

            pathlib.Path(".results/screenshots").mkdir(exist_ok=True, parents=True)
            imageio.imwrite(f".results/screenshots/lynx_view_{int(time.time())}.png", img)

            while viewer.is_running():
                step_start = time.time()
                mujoco.mj_step(model, data)

                viewer.sync()
                time_until_next_step = model.opt.timestep - (time.time() - step_start)
                if time_until_next_step > 0:
                    time.sleep(time_until_next_step)

image.png