Skip to content

Webots Simulator Backend

Run trajectories in the Webots robotics simulator.

Overview

WebotsBackend integrates with the Webots simulator, allowing you to test trajectories in a physics-based simulation environment.

WebotsBackend Class

WebotsBackend

WebotsBackend(host='localhost', port=9090, step_ms=50)

Bases: RobotBackend

Execute trajectories in Webots simulator.

Must be instantiated from within a Webots controller script.

Webots interprets motor positions as relative to the base position at simulation time zero. On connect, the backend reads each joint's initial position and stores it as a per-joint offset. All position commands are then converted from absolute radians to Webots-relative positions using these offsets. After _reset_to_zero() the offsets become 0.0 (since all joints are driven to absolute zero), so commanding 0 rad targets the proto-defined zero.

When reading joint positions, the backend waits for motor readings to stabilize (same value twice) to ensure accurate readings when motors are in motion. Use the timeout parameter in get_joints() to control how long to wait (default: 5.0 seconds).

Example

In your Webots controller file:

from pib3.backends import WebotsBackend

with WebotsBackend() as backend: backend.run_trajectory("trajectory.json")

# Read joint positions (waits up to 5s for stabilization)
joints = backend.get_joints()

# Read with custom timeout
joints = backend.get_joints(timeout=2.0)

Initialize Webots backend.

Parameters:

Name Type Description Default
host str

Webots host (unused).

'localhost'
port int

Webots port (unused).

9090
step_ms int

Time step per waypoint in milliseconds.

50

Quick Start

# In your Webots controller file:
from pib3.backends import WebotsBackend

with WebotsBackend() as backend:
    backend.run_trajectory("trajectory.json")

Webots Environment Required

This backend must be instantiated from within a Webots controller script. It cannot be used standalone.


Constructor

WebotsBackend(step_ms: int = 50)

Parameters:

Parameter Type Default Description
step_ms int 50 Simulation time step per waypoint in milliseconds. Smaller values give smoother motion but slower playback.

Example:

from pib3.backends import WebotsBackend

# Default: 50ms per step
backend = WebotsBackend()

# Custom step timing (slower, smoother)
backend = WebotsBackend(step_ms=100)

# Faster playback
backend = WebotsBackend(step_ms=20)

Connection

connect()

Initialize Webots robot and motor devices.

def connect(self) -> None

Raises:

  • ImportError: If not running from within a Webots controller

Example:

from pib3.backends import WebotsBackend

backend = WebotsBackend()
backend.connect()  # Initializes robot and motors
# ... use backend ...
backend.disconnect()

Using Context Manager

The recommended way to use the Webots backend:

from pib3 import Joint
from pib3.backends import WebotsBackend

with WebotsBackend() as backend:
    # Robot automatically initialized
    backend.set_joint(Joint.ELBOW_LEFT, 50.0)
# Cleanup handled automatically

Joint Control

The Webots backend inherits all methods from RobotBackend. Key methods:

set_joint()

Set a single joint position.

def set_joint(
    self,
    motor_name: str,
    position: float,
    unit: Literal["percent", "rad"] = "percent",
    async_: bool = True,
    timeout: float = 1.0,
    tolerance: Optional[float] = None,
) -> bool

Parameters:

Parameter Type Default Description
motor_name str required Motor name (e.g., "elbow_left").
position float required Target position (0-100 for percent, radians for rad).
unit "percent" or "rad" "percent" Position unit.
async_ bool True If True, return immediately. If False, wait for joint to reach target.
timeout float 1.0 Max wait time (only used when async_=False).
tolerance float or None None Acceptable error (2.0% or 0.05 rad default).

Returns: bool - True if successful.

Example:

from pib3 import Joint

with WebotsBackend() as robot:
    # Set individual joints
    robot.set_joint(Joint.ELBOW_LEFT, 50.0)  # 50%

    # Using radians
    robot.set_joint(Joint.ELBOW_LEFT, 1.25, unit="rad")

set_joints()

Set multiple joint positions simultaneously.

def set_joints(
    self,
    positions: Union[Dict[str, float], Sequence[float]],
    unit: Literal["percent", "rad"] = "percent",
    async_: bool = True,
    timeout: float = 1.0,
    tolerance: Optional[float] = None,
) -> bool

Parameters:

Parameter Type Default Description
positions Dict[str, float] or Sequence[float] required Target positions as dict or sequence.
unit "percent" or "rad" "percent" Position unit.
async_ bool True If True, return immediately. If False, wait for joints to reach targets.
timeout float 1.0 Max wait time (only used when async_=False).
tolerance float or None None Acceptable error.

Example:

with WebotsBackend() as robot:
    robot.set_joints({
        "shoulder_vertical_left": 30.0,
        "shoulder_horizontal_left": 40.0,
        "elbow_left": 60.0,
    })

get_joint()

Read a single joint position. Waits for motor readings to stabilize (same value twice) before returning.

def get_joint(
    self,
    motor_name: str,
    unit: Literal["percent", "rad"] = "percent",
    timeout: Optional[float] = None,
) -> Optional[float]

Parameters:

Parameter Type Default Description
motor_name str required Motor name to query.
unit "percent" or "rad" "percent" Return unit.
timeout float or None 5.0 Max time to wait for motor reading to stabilize (seconds).

Returns: float or None - Current position, or None if unavailable or motor still moving.

Example:

from pib3 import Joint

with WebotsBackend() as robot:
    # Uses default 5s timeout for stabilization
    pos = robot.get_joint(Joint.ELBOW_LEFT)
    print(f"Elbow at {pos:.1f}%")

    # Shorter timeout
    pos = robot.get_joint(Joint.ELBOW_LEFT, timeout=1.0)

get_joints()

Read multiple joint positions. Waits for each motor reading to stabilize before returning.

def get_joints(
    self,
    motor_names: Optional[List[str]] = None,
    unit: Literal["percent", "rad"] = "percent",
    timeout: Optional[float] = None,
) -> Dict[str, float]

Parameters:

Parameter Type Default Description
motor_names List[str] or None None Motors to query. None returns all.
unit "percent" or "rad" "percent" Return unit.
timeout float or None 5.0 Max time to wait for each motor reading to stabilize (seconds).

Returns: Dict[str, float] - Motor names mapped to positions.


Trajectory Execution

run_trajectory()

Execute a trajectory in simulation.

def run_trajectory(
    self,
    trajectory: Union[str, Path, Trajectory],
    rate_hz: float = 20.0,
    progress_callback: Optional[Callable[[int, int], None]] = None,
) -> bool

Parameters:

Parameter Type Default Description
trajectory str, Path, or Trajectory required Trajectory file path or object.
rate_hz float 20.0 Playback rate (waypoints per second).
progress_callback Callable[[int, int], None] or None None Progress callback (current, total).

Returns: bool - True if completed successfully.

Example:

from pib3.backends import WebotsBackend
from pib3 import Trajectory

trajectory = Trajectory.from_json("trajectory.json")

def on_progress(current, total):
    print(f"\rProgress: {current}/{total}", end="")

with WebotsBackend() as robot:
    robot.run_trajectory(
        trajectory,
        rate_hz=20.0,
        progress_callback=on_progress,
    )
    print("\nDone!")

Motor Mapping

The backend maps trajectory joint names to Webots motor device names:

Trajectory Name Webots Motor
turn_head_motor head_horizontal
tilt_forward_motor head_vertical
shoulder_vertical_left shoulder_vertical_left
shoulder_horizontal_left shoulder_horizontal_left
upper_arm_left_rotation upper_arm_left
elbow_left elbow_left
lower_arm_left_rotation forearm_left
wrist_left wrist_left
thumb_left_opposition thumb_left_opposition
thumb_left_stretch thumb_left_distal

Similar mappings exist for right arm and remaining fingers.


Coordinate System

The canonical format uses Webots motor radians directly. No offset is needed:

Webots_position = Canonical_radians  (no offset)

Webots motors use sensible radian ranges (e.g., -π/2 to +π/2 for the head motor).


Webots Project Setup

Directory Structure

my_webots_project/
├── worlds/
│   └── pib_world.wbt
├── controllers/
│   └── pib_controller/
│       └── pib_controller.py
└── protos/
    └── pib.proto

Controller Script Example

Create a controller file pib_controller.py:

"""PIB robot controller for Webots."""
from pib3.backends import WebotsBackend

def main():
    with WebotsBackend() as robot:
        # Run a pre-generated trajectory
        robot.run_trajectory("trajectory.json")

if __name__ == "__main__":
    main()

World File Configuration

In your .wbt world file, configure the robot to use your controller:

Robot {
  controller "pib_controller"
  ...
}

Examples

Wave Animation

from pib3 import Joint
from pib3.backends import WebotsBackend

with WebotsBackend() as robot:
    # Raise arm (async_=False waits for motor to reach position)
    robot.set_joint(Joint.SHOULDER_VERTICAL_LEFT, 30.0, async_=False)

    # Wave back and forth
    for _ in range(5):
        robot.set_joint(Joint.WRIST_LEFT, 20.0, async_=False)
        robot.set_joint(Joint.WRIST_LEFT, 80.0, async_=False)

    # Return to neutral
    robot.set_joint(Joint.WRIST_LEFT, 50.0, async_=False)
    robot.set_joint(Joint.SHOULDER_VERTICAL_LEFT, 50.0, async_=False)

Use async_=False instead of time.sleep()

In Webots, simulation time only advances when robot.step() is called internally. Using time.sleep() wastes wall-clock time without advancing the simulation. The async_=False parameter automatically steps the simulation until motors reach their targets.

Complete Drawing Session

from pib3.backends import WebotsBackend
import pib3

# Generate trajectory from image (outside Webots)
trajectory = pib3.generate_trajectory("drawing.png")
trajectory.to_json("drawing_trajectory.json")

# Execute in Webots (in controller)
with WebotsBackend() as robot:
    robot.run_trajectory("drawing_trajectory.json", rate_hz=30.0)

Troubleshooting

ImportError: No module named 'controller'

Cause: Not running from within Webots.

Solution: This backend must be used in a Webots controller script. It cannot be run standalone from the command line.

Motor Not Found

Cause: Motor name mismatch between trajectory and Webots model.

Solution: Check that the motor names in your Webots proto file match the expected names in JOINT_TO_WEBOTS_MOTOR.

Simulation Runs Too Fast/Slow

Cause: Step timing mismatch.

Solution: Adjust the step_ms parameter or rate_hz:

# Slower, more accurate simulation
backend = WebotsBackend(step_ms=100)

# Faster simulation
backend = WebotsBackend(step_ms=20)

# Match rate_hz to timestep (for 50ms, use 20 Hz)
robot.run_trajectory(trajectory, rate_hz=20.0)

Robot Doesn't Move Smoothly

Cause: Step timing too large.

Solution: Use smaller step_ms values for smoother motion:

backend = WebotsBackend(step_ms=20)  # Smoother

Motors Don't Reach Target Position

Cause: Using async_=True (default) only steps simulation once.

Solution: Use async_=False to wait for motors to reach their targets:

# Wrong - returns immediately, motor barely moves
robot.set_joint(Joint.ELBOW_LEFT, 50.0)

# Correct - waits for motor to reach position
robot.set_joint(Joint.ELBOW_LEFT, 50.0, async_=False)

This also ensures code compatibility with the real robot, which behaves the same way.