Webots
Webots is an open-source, multi-platform 3D robot simulator that serves as a complete development environment for modeling, programming, and simulating robots, vehicles, and mechanical systems.[1] Developed and maintained by Cyberbotics Ltd., a spin-off from the Swiss Federal Institute of Technology in Lausanne (EPFL), Webots originated from research at the Laboratoire de Micro-Informatique (LAMI) and has been publicly available since 1998, becoming open-source in 2018.[2] It supports Windows, Linux, and macOS operating systems, enabling users to create realistic simulations with physics-based interactions, sensor modeling, and actuator controls.[1]
Key features of Webots include a modern graphical user interface built with Qt, a customized fork of the Open Dynamics Engine (ODE) for physics simulation, and rendering capabilities powered by the Wren library using OpenGL 3.3 for high-fidelity visuals.[1] The simulator's application programming interface (API) is straightforward and supports programming in languages such as C, C++, Python, Java, MATLAB, and integration with the Robot Operating System (ROS), allowing for cross-compilation and remote control of physical robots.[1] Simulations can be exported as movies, interactive HTML scenes, or real-time streams via WebGL and WebSockets, facilitating sharing and web-based demonstrations.[1]
Webots is widely adopted in academia, industry, and research for tasks including algorithm prototyping, AI and machine learning development for robotics, and educational training in control systems.[3] It accommodates a broad range of robotic platforms, from simple two-wheeled mobile robots and industrial manipulators to drones, legged robots, and autonomous vehicles, within both indoor and outdoor virtual environments.[1] The project's open-source nature, licensed under the Apache License 2.0 since 2018, encourages community contributions through its GitHub repository, while extensive documentation, tutorials, and testing ensure reliability and deterministic behavior in simulations.[4]
Introduction
Overview
Webots is a free and open-source 3D robot simulator designed for modeling, programming, and simulating robots, vehicles, and mechanical systems.[4][5] It provides a complete development environment that enables users to create realistic virtual worlds with physics properties, sensors, actuators, and various locomotion types such as wheeled, legged, or flying mechanisms.[5] Originally developed at the Swiss Federal Institute of Technology in Lausanne (EPFL) in 1996, Webots has evolved into a versatile tool for robotics applications.[4]
The simulator is widely used in industry, education, and research for rapid prototyping and testing of robotic systems, including applications in automotive design, toy development, multi-agent coordination, and adaptive behaviors.[5] Its physics-based simulation, powered by a fork of the Open Dynamics Engine (ODE), allows for accurate modeling of rigid body dynamics, collisions, and environmental interactions.[6] This makes it suitable for exploring complex scenarios without the need for physical hardware, reducing costs and risks in development cycles.[5]
Webots is beginner-friendly, offering intuitive tools and example models to introduce newcomers to robotics concepts.[4] It supports multiple platforms, including Windows, Linux, and macOS, ensuring broad accessibility for users across different operating systems.[1] The latest version, R2025a, was released on January 31, 2025, incorporating new features, improvements, and bug fixes to enhance simulation capabilities.[7]
History and Development
Webots was initially designed in 1996 at the Laboratoire de Micro-Informatique (LAMI) of the Swiss Federal Institute of Technology in Lausanne (EPFL), Switzerland, as a research tool for developing and testing mobile robotics control algorithms.[8][4] The project originated from efforts to create a flexible simulation environment that allowed researchers to prototype robot behaviors without physical hardware.[9]
In 1998, Cyberbotics Ltd. was founded as a spin-off from EPFL by Olivier Michel, who transitioned Webots into a commercial product, marking the beginning of its proprietary development and sales phase.[10][4] The company, based in Switzerland, focused on enhancing the simulator's capabilities for professional use in robotics research and industry.[11] This commercialization enabled broader adoption while sustaining ongoing improvements under a closed-source model for over two decades.[12]
A significant milestone occurred in December 2018 with the release of Webots R2019a, when the software transitioned to fully open-source under the Apache 2.0 license, making it freely available to the global community.[12] Since then, development has been hosted on GitHub, where Cyberbotics continues to lead enhancements supported by customer services, while inviting community contributions through pull requests and issue reporting.[4]
Key version releases have introduced substantial updates, reflecting the simulator's evolution. For instance, R2020b, released in July 2020, added several new robot models including Spot from Boston Dynamics.[13] R2022a, launched in December 2021, implemented major axis system changes, switching the global coordinate system to ENU (East-North-Up) and object axes to FLU (Forward-Left-Up) for better compatibility with modern robotics standards.[14] R2023a, released in November 2022, incorporated the ROSbot from Husarion along with supporting device models like the MPU-9250 IMU.[15] Most recently, R2025a in January 2025 introduced the Heron USV model from Clearpath Robotics and renamed the web scene format to W3D for streamlined workflows.[16]
Core Features
Simulation Engine
Webots employs a customized fork of the Open Dynamics Engine (ODE) as its physics simulation backend, enabling accurate modeling of rigid body dynamics, collision detection, and joint constraints in robotic environments.[1][6] This integration allows for realistic interactions such as forces, torques, and mass properties, with parameters like density, center of mass, and inertia matrices passed directly to ODE for computation.[17] The physics engine supports configurable elements including damping and restitution, ensuring stable simulations for complex mechanisms like wheeled or articulated robots.
For 3D visualization, Webots utilizes the Wren rendering engine, a bespoke system built on OpenGL 3.3 that provides high-fidelity graphics rendering.[18][19] Wren handles advanced features such as texture mapping, physically-based rendering with high dynamic range (HDR) lighting, and real-time shadows, allowing users to observe detailed environmental and robotic behaviors without compromising simulation performance.[12]
The simulator operates in multiple modes to suit different workflows: real-time mode synchronizes simulation speed with wall-clock time for lifelike testing; fast-forward mode accelerates computations using available CPU resources, ideal for long-duration runs; and paused mode halts progression for inspection or debugging.[20][21] These modes facilitate multi-robot simulations, enabling scenarios with numerous interacting entities while maintaining computational efficiency.[22]
World construction leverages PROTO files, which encapsulate reusable node definitions for modular assembly of scenes, vehicles, or environments.[23] Additionally, Webots imports 3D assets from CAD-compatible formats like OBJ and DAE via the CadShape node, streamlining the integration of external geometries into the simulation.[24] Core parameters include a default time step of 32 milliseconds for control and physics updates, gravity set to 9.81 m/s² downward via the WorldInfo node, and friction modeled through Coulomb coefficients in ContactProperties nodes, ranging from 0 (frictionless) to infinity.[25][26][27]
Webots provides native support for Windows, Linux distributions such as Ubuntu and Debian, and macOS, operating on x86_64 architectures across all platforms and ARM architectures on macOS via Apple Silicon with Rosetta compatibility where needed.[28] This cross-platform compatibility enables developers to run simulations consistently across desktop environments without significant reconfiguration.[28]
The simulator supports controller development in several programming languages, including C, C++, Python, Java, and MATLAB, allowing users to select based on project requirements and familiarity.[29] Additionally, external controllers can interface with Webots over TCP/IP for remote or third-party integrations, facilitating communication between the simulator and custom applications.[30] Since release R2023a, Python support has been enhanced with a new API compatible with any current and future Python versions (3.7 and above), improving flexibility for interpreted scripting.[31]
Webots includes a built-in compiler for C and C++ controllers, utilizing tools like MinGW on Windows and gcc on Linux, which streamlines the build process directly within the editor.[32] It also integrates with external IDEs such as Visual Studio Code through Makefile configurations and community extensions, enabling advanced editing, debugging, and cross-compilation workflows, including Windows Subsystem for Linux (WSL) for hybrid development environments.[33]
For deployment, Webots allows exporting compiled controller binaries for standalone simulation execution without the full source codebase, supporting offline and distributed testing scenarios.[34] Cloud-based simulations are enabled through webots.cloud, an open-source service for sharing interactive 3D scenes, animations, and live streams accessible via web browsers.[35]
User Interface
Main Windows and Components
The Webots user interface is primarily composed of four principal windows that facilitate interaction with the simulation environment: the 3D window, the Scene Tree, the Text Editor (a built-in text editor for controllers), and the Console.[20] These components provide a graphical means to visualize, edit, and manage simulations without requiring external tools for basic operations. The interface also includes a menu bar at the top for accessing core functions, ensuring a streamlined workflow for users developing and testing robot simulations.[20]
The 3D window, located at the center of the main interface, renders a real-time 3D representation of the simulated world using OpenGL.[36] It allows users to interact with the scene by selecting objects such as robots or solids via left-clicking, and supports camera controls for navigation: orbiting the viewpoint by left-dragging on the background (horizontal for yaw, vertical for pitch), panning by right-dragging, and zooming via mouse wheel or combined left-right dragging.[36] Additional features include optional visualizations like contact points or lidar ray paths for debugging, accessible through the View menu.[36]
The Scene Tree, typically docked on the left side, presents a hierarchical tree view of the world's structure, mirroring the VRML97-like node organization including robots, solids, and environmental elements.[37] Users can expand or collapse nodes to select and edit fields by double-clicking, with changes updating instantly in the 3D window; right-clicking provides context menus for actions like adding child nodes or resetting fields.[37] It serves as the primary entry point for world editing, such as modifying the basicTimeStep in the WorldInfo node.[37]
The Text Editor opens as a dedicated multi-tab text editor when a robot node is selected in the Scene Tree and the "Open Robot Window" option is chosen, or via the File menu for controller files.[38] Tailored for Webots controllers, it includes syntax highlighting, auto-completion for API functions, and buttons for building (compiling) and running the code directly within the interface.[38] This window supports languages like C, C++, Python, Java, and MATLAB, enabling quick iteration on controller logic without switching applications.[38]
The Console, positioned at the bottom or as a separate pane, captures output from simulation runs, including compilation errors (displayed in red), controller logs, and sensor data streams.[20] Multiple consoles can be created via the Tools menu for isolating outputs from different controllers, and they can be cleared individually or all at once to maintain clarity during debugging.[20]
The menu bar spans the top of the interface with eight primary menus: File for world and project operations (e.g., open, save, new); Edit for standard editing actions; View for display modes (e.g., wireframe, solid, fullscreen); Simulation for control actions (e.g., step, run, pause, real-time mode); Build for controller compilation; Overlays for device visualizations; Tools for additional utilities such as the Scene Tree visibility; and Help for documentation access.[20] Users can customize the interface layout, including language and startup mode, through the Preferences dialog accessible via the Tools menu.[39]
Webots provides intuitive editing and navigation tools within its user interface, enabling users to interactively modify the simulation environment. Selection of objects occurs by left-clicking on Solid nodes in the 3D window, which displays a bounding box with white lines outlining the object; pink lines indicate collision boundaries, while blue appears when idle.[36] To select subparts of a Solid, users hold the Alt key (or Alt+Ctrl on Linux) during clicking. Double-clicking a Robot node opens its dedicated editor window. Right-clicking a selected object brings up a context menu for actions such as copying, deleting, or aligning the viewpoint.[36]
Manipulation of selected objects uses bounding box handles for precise control: users click and drag axis-aligned handles to translate or rotate along specific directions. For freeform movement, holding Shift while left-click-dragging translates the object parallel to the ground plane, right-click-dragging rotates around the vertical axis, and using the mouse wheel or Shift with both buttons lifts it vertically. Applying forces or torques is possible by holding Alt (or Alt+Ctrl on Linux) and dragging with the left or right mouse button, simulating physical interactions during editing. Scaling is handled through the scale field in the node's Transform properties rather than direct 3D handles. The Scene tree serves as the entry point for these operations, where nodes are selected and manipulated in a hierarchical view.[36][37]
Navigation in the 3D window relies on mouse interactions: left-click-dragging rotates the viewpoint around the scene, right-click-dragging translates it, and the mouse wheel or middle button zooms in and out (Ctrl+mouse on macOS). Users can lock the viewpoint with the "Lock Viewpoint" option or follow a specific object via the context menu's "Follow Object" command, which dynamically adjusts the camera to track the selected item during simulation. Restoring the initial view is done through "Restore Viewpoint," and predefined alignments like top or side views are accessible via the "Change View" menu. The main toolbar includes simulation controls such as play, pause, and a virtual time counter for stepping through animations, though no dedicated timeline slider is provided.[36][20]
Editing tools facilitate adding and removing nodes through the toolbar's "Add" button or the Scene tree's context menu (right-click for insert, cut, copy, paste, or delete options). The property editor, integrated at the bottom of the Scene tree, allows direct modification of node fields: double-clicking a field (e.g., translation or rotation) enables editing via text input, arrow keys for numeric adjustments, or checkboxes toggled with the Space bar; changes update the 3D view immediately upon confirmation with Enter. Context menus in the 3D window or Scene tree provide quick access to these tools for efficient workflow.[37][20]
Visualization aids enhance editing precision via the "View > Optional Rendering" submenu. The "Show All Bounding Objects" option displays bounding volumes (e.g., spheres or boxes) as wireframes—white for general outlines, pink for collision detection—allowing users to verify spatial relationships. "Show Coordinate System" overlays axis indicators (red for X, green for Y, blue for Z) in the window's corner for orientation reference. Collision overlays appear through "Show Contact Points," highlighting interaction points after simulation steps, while "Show Normals" renders surface normals as magenta lines to aid geometry inspection. These aids are toggleable and do not affect robot camera renders.[20][36]
Import and export functionalities support interoperability with standard formats. Users import VRML97 (.wrl) or OBJ files via "File > Open World" or the "Add Node > Import" dialog, converting them into Webots nodes for editing. Export options include saving worlds as VRML97 files ("File > Export VRML97") or X3D for web integration, preserving geometry and structure. Additionally, webots.cloud enables sharing of exported simulations online, allowing viewing in a browser without local installation.[20][40]
Robot Modeling
Scene Hierarchy and Nodes
The scene hierarchy in Webots is a node-based system that structures simulated worlds using a tree-like organization, drawing from VRML97 standards while incorporating robotics-specific extensions. At the root of this hierarchy is the WorldInfo node, which encapsulates global world parameters such as the coordinate system and basic simulation settings, serving as the foundational container for all other elements.[41][42] This hierarchical approach allows users to assemble complex scenes by nesting nodes, where parent-child relationships define spatial and functional dependencies, enabling the construction of robots and environments through modular composition.[37]
Central to robot modeling are the Robot and Solid nodes, which form the backbone of physical assemblies. The Robot node acts as a container for devices and sub-components, featuring fields like boundingObject to specify collision geometry and children to include subordinate nodes, such as positioning a wheel as a child of a chassis for hierarchical assembly.[37][41] Solid nodes, inheriting from the Pose node, represent tangible objects with fields for geometry (defining visual and collision shapes) and physics (specifying mass, inertia, and dynamics), allowing precise placement and interaction within the scene.[41][43] Device nodes, such as PositionSensor for detecting joint positions or Motor for actuation, are specialized extensions that must typically reside within a Robot's children field to integrate sensors and actuators into the robot's structure.[37][41][44]
Fields within nodes provide the data structures for customization, using single-value (SF) and multi-value (MF) types to handle diverse parameters. For instance, SFVec3f fields store three-dimensional vectors for positions and translations, while MFFloat fields manage arrays of floating-point numbers, such as sequences of joint angles or sensor thresholds.[42] To enhance reusability, Webots supports PROTO nodes, which allow users to define custom, parameterized node types as reusable templates, encapsulating complex assemblies like a standardized robot arm for repeated instantiation across worlds.[37][42]
For effective scene design, Webots employs DEF and USE mechanisms to promote modularity and efficiency. The DEF keyword assigns a unique identifier to a node instance, enabling its replication via USE references, which avoids redundant definitions and supports instancing of identical components, such as multiple identical wheels in a vehicle model.[42] Best practices emphasize shallow hierarchies to optimize simulation performance, as deeply nested structures can increase computational overhead during traversal and updates, while modular use of PROTO and DEF/USE fosters maintainable, scalable worlds.[37]
Physics Simulation and Rendering
Webots simulates physical interactions in modeled scenes through configurable parameters applied to nodes, enabling realistic dynamics for robots and environments. Physical properties for solid objects are defined using the Solid node, where users specify mass (in kilograms) or density (in kg/m³) to compute the total mass based on the bounding object's volume; if neither is set to -1, mass overrides density calculations. Inertia is handled via the inertiaMatrix field, which accepts a 2x3 matrix of values in kg·m² for principal moments and products of inertia, or is automatically computed if unspecified. Connections between solids, such as robot joints, utilize nodes like HingeJoint for single-axis rotational freedom or BallJoint for spherical motion, with parameters including axis orientation, limits, and suspension for stability. Contact interactions between objects are governed by ContactProperties nodes, which define coulombFriction coefficients (ranging from 0 to infinity, supporting symmetric or asymmetric modes) for sliding resistance and bounce (0 to 1) for restitution, along with a minimum bounceVelocity threshold in m/s to activate elastic responses.[43][45][27]
Simulation accuracy is controlled by the presence of a Physics node in the world, which activates dynamic mode using an ODE fork for force-based computations, contrasting with kinematic mode (absent Physics node) that relies on direct position updates without collision forces. Key parameters include the WorldInfo node's basicTimeStep (default 32 ms, minimum 1 ms), where smaller values enhance precision in collision detection and motion stability but increase computational load. Solver behavior is tuned via ERP (Error Reduction Parameter, default 0.2, range 0-1) to correct joint errors proportionally per step and CFM (Constraint Force Mixing, default 0.00001) to soften constraints, preventing excessive rigidity; higher ERP values improve stability at the cost of speed, while lower CFM reduces penetration in fast collisions. Advanced modes allow physics plugins for custom solvers, but basic configurations prioritize stability through iterative damping and implicit solid merging to avoid redundant computations.[17][26]
Rendering in Webots leverages the Wren engine, an OpenGL 3.3 implementation supporting physically based rendering (PBR) for lifelike visuals. Materials are configured via PBRAppearance nodes, incorporating textures for base color, normal/bump mapping, metallic/roughness properties, and emissive effects to simulate surface realism without manual shader coding. Lighting includes DirectionalLight for infinite sources like sunlight, PointLight for localized illumination with attenuation, and SpotLight for focused beams, all contributing to shadow casting and ambient occlusion when enabled. Atmospheric effects are added using the Fog node, which blends object colors toward a specified fogColor based on distance, with density controlling exponential or linear fade rates for depth simulation. Texture mapping applies images to geometries via fields in Appearance nodes, while custom shaders enable post-processing like bloom or depth-of-field in sample worlds.[1][46][47][48]
Optimization for large scenes involves physics and rendering adjustments to maintain performance. In physics, the physicsDisableTime field (default 1 s) automatically deactivates idle solids below linear (0.01 m/s) or angular (0.01 rad/s) velocity thresholds, reducing computations for static elements. Rendering optimizations include OpenGL preferences for texture quality (high/medium/low resolutions to cut GPU load), disabling shadows or anti-aliasing (SMAA) for older hardware, and ambient occlusion levels (medium/ultra) to balance quality and speed; frustum culling is handled internally by Wren to skip off-screen objects. Users can employ Level of Detail (LOD) through custom PROTO nodes grouping simplified geometries for distant views, though no built-in LOD node exists.[26][39]
Common issues like tunneling—where fast objects pass through solids—or simulation instability arise from large time steps or stiff constraints, resolvable by reducing basicTimeStep to 16 ms or below for finer integration, increasing ERP to 0.4-0.8 for better error correction, or lowering CFM to minimize drift; contact material tweaks, such as raising bounce or friction, also prevent sinking or slipping without altering core solver iterations, which remain fixed in the ODE backend.[26]
Controller Programming
API and Controller Structure
The Webots controller API provides a structured interface for programming robot behaviors within the simulation environment, enabling developers to interact with simulated sensors, actuators, and the overall simulation state. The API is designed to be language-agnostic where possible, with core functions available across supported languages, though explicit initialization and cleanup are primarily required in the C API. This structure ensures deterministic control loops synchronized with the simulator's physics engine, facilitating real-time robot operation.[25]
The controller lifecycle follows a standardized sequence to manage initialization, execution, and termination. It begins with wb_robot_init(), which establishes communication between the controller and the Webots simulator, setting up the necessary library resources; this step is essential in the C API but handled automatically in other bindings like Python. The main execution occurs in a loop calling wb_robot_step(duration), where duration specifies the simulation time step in milliseconds—typically matching the worldInfo.basicTimeStep field for synchronization—and the function returns -1 to signal simulation termination, prompting the controller to exit gracefully. The lifecycle concludes with wb_robot_cleanup(), which releases resources and closes the communication channel, ensuring a clean shutdown in the C API.[49][25]
Key API categories encompass robot-level functions and device management. Robot functions include wb_robot_get_time(), which retrieves the elapsed simulation time in seconds since the start, and wb_robot_get_mode(), which returns the current operating mode such as simulation, real-time, or supervisor mode to adapt controller logic accordingly. Device access is facilitated by wb_robot_get_device(name), which returns a handle to a named device like a sensor or motor, allowing subsequent operations; sensors can then be enabled with wb_device_enable(samplingPeriod) to start data collection at specified intervals, and disabled with wb_device_disable() when no longer needed.[49][25]
Sensors in the API allow reading of simulated environmental data once enabled, with functions tailored to device types; for instance, wb_distance_sensor_get_value() returns the measured distance as a floating-point value, while vector-based sensors like accelerometers provide arrays via similar get_value() calls. Actuators enable control actions, such as wb_motor_set_position(target) to command a motor to a specific angular or linear position, or wb_motor_set_velocity(velocity) for speed-based actuation, with targets applied during the next simulation step. These operations ensure actuators influence the physics simulation predictably.[49]
Communication features support inter-robot or external interactions through emitter and receiver devices. An emitter sends messages via wb_emitter_send(data, size), broadcasting packets that receivers can capture with wb_receiver_get_data() and wb_receiver_next_packet(), enabling coordinated behaviors like flocking or data exchange in multi-robot scenarios. In supervisor mode—activated by setting the robot's supervisor field to TRUE—the API extends to global simulation control, such as accessing other nodes or modifying the scene, though changes require reloading the world for persistence.[21]
Error handling in the API relies on return codes and logging mechanisms for robustness. Functions like wb_robot_step() return -1 to indicate errors such as simulation end or invalid parameters, requiring controllers to check these values and invoke cleanup to avoid resource leaks. Logging is managed through wb_robot_console_print(text, color), which outputs messages to the Webots console with optional color formatting for debugging, or via standard output streams in non-C bindings, aiding in tracing controller execution without halting the simulation.[49][25]
Programming Examples
Programming examples in Webots demonstrate how controllers interact with the simulation environment through the Webots API, enabling robots to perceive their surroundings via sensors and actuate devices like motors. These examples are typically implemented in the main loop of the controller program, where the simulation is advanced using the wb_robot_step() function (or equivalent in other languages), ensuring synchronized updates between the controller and the physics engine.[25]
A basic example involves programming a simple wheeled robot to move forward continuously. In C, the controller initializes the robot and a motor device, sets the motor to an infinite position target to allow velocity control, and enters a loop that steps the simulation at a fixed time interval, such as 32 milliseconds. The code snippet below illustrates this for a single motor setup, commonly used in introductory simulations like the e-puck robot:
c
#include <webots/robot.h>
#include <webots/motor.h>
#define TIME_STEP 32
int main(int argc, char **argv) {
wb_robot_init();
WbDeviceTag motor = wb_robot_get_device("motor");
wb_motor_set_position(motor, INFINITY);
wb_motor_set_velocity(motor, 1.0);
while (wb_robot_step(TIME_STEP) != -1) {
// Empty [loop](/page/Loop) body for continuous motion
}
wb_robot_cleanup();
return 0;
}
#include <webots/robot.h>
#include <webots/motor.h>
#define TIME_STEP 32
int main(int argc, char **argv) {
wb_robot_init();
WbDeviceTag motor = wb_robot_get_device("motor");
wb_motor_set_position(motor, INFINITY);
wb_motor_set_velocity(motor, 1.0);
while (wb_robot_step(TIME_STEP) != -1) {
// Empty [loop](/page/Loop) body for continuous motion
}
wb_robot_cleanup();
return 0;
}
This approach ensures the robot maintains a constant forward velocity until the simulation ends or an external termination condition is met.[25] Similar implementations exist in Python and Java, replacing C functions with object-oriented equivalents like Robot() and getDevice(), while preserving the initialization, setup, and stepping structure.[25]
For sensor-actuator interactions, an obstacle avoidance example uses distance sensors to detect nearby objects and adjust motor velocities accordingly, implementing a reactive behavior in a differential drive robot. In Python, the controller enables two distance sensors, reads their values in each simulation step, and computes differential speeds to steer away from obstacles—for instance, turning right if the left sensor detects a closer barrier. The following snippet shows the core structure:
python
from controller import [Robot](/page/Robot), Motor, [DistanceSensor](/page/Sensor)
TIME_STEP = 32
robot = Robot()
left_sensor = robot.getDevice("left_sensor")
right_sensor = robot.getDevice("right_sensor")
left_sensor.enable(TIME_STEP)
right_sensor.enable(TIME_STEP)
left_motor = robot.getDevice("left_motor")
right_motor = robot.getDevice("right_motor")
left_motor.setPosition(float('inf'))
right_motor.setPosition(float('inf'))
while robot.step(TIME_STEP) != -1:
left_value = left_sensor.getValue()
right_value = right_sensor.getValue()
# Simple avoidance logic: adjust speeds based on sensor thresholds
left_speed = 1.0 if left_value > 80 else -1.0
right_speed = 1.0 if right_value > 80 else -1.0
left_motor.setVelocity(left_speed)
right_motor.setVelocity(right_speed)
from controller import [Robot](/page/Robot), Motor, [DistanceSensor](/page/Sensor)
TIME_STEP = 32
robot = Robot()
left_sensor = robot.getDevice("left_sensor")
right_sensor = robot.getDevice("right_sensor")
left_sensor.enable(TIME_STEP)
right_sensor.enable(TIME_STEP)
left_motor = robot.getDevice("left_motor")
right_motor = robot.getDevice("right_motor")
left_motor.setPosition(float('inf'))
right_motor.setPosition(float('inf'))
while robot.step(TIME_STEP) != -1:
left_value = left_sensor.getValue()
right_value = right_sensor.getValue()
# Simple avoidance logic: adjust speeds based on sensor thresholds
left_speed = 1.0 if left_value > 80 else -1.0
right_speed = 1.0 if right_value > 80 else -1.0
left_motor.setVelocity(left_speed)
right_motor.setVelocity(right_speed)
This loop integrates perception and action, with sensor values typically ranging from 0 to 4095 based on proximity, allowing the robot to navigate dynamically without predefined paths.[25]
In multi-device scenarios, such as manipulating a robotic arm, controllers coordinate position sensors with motors to achieve precise movements, often using feedback loops for incremental positioning. In Java, the program enables a position sensor on the arm joint, reads its current value in each step, and sets the motor to a slightly offset target position to simulate controlled extension or retraction. An example code fragment is:
java
import com.cyberbotics.webots.controller.*;
public class ArmController {
public static void main([String](/page/String)[] args) {
final [int](/page/INT) TIME_STEP = [32](/page/32);
[Robot](/page/Robot) robot = new [Robot](/page/Robot)();
Motor motor = robot.getMotor("arm_motor");
[Position](/page/Position)Sensor sensor = robot.getPositionSensor("arm_sensor");
sensor.enable(TIME_STEP);
// [Position](/page/Position) control
while (robot.step(TIME_STEP) != -[1](/page/1)) {
double current_pos = sensor.getValue();
motor.setPosition(current_pos + 0.1); // Incremental adjustment
}
}
}
import com.cyberbotics.webots.controller.*;
public class ArmController {
public static void main([String](/page/String)[] args) {
final [int](/page/INT) TIME_STEP = [32](/page/32);
[Robot](/page/Robot) robot = new [Robot](/page/Robot)();
Motor motor = robot.getMotor("arm_motor");
[Position](/page/Position)Sensor sensor = robot.getPositionSensor("arm_sensor");
sensor.enable(TIME_STEP);
// [Position](/page/Position) control
while (robot.step(TIME_STEP) != -[1](/page/1)) {
double current_pos = sensor.getValue();
motor.setPosition(current_pos + 0.1); // Incremental adjustment
}
}
}
This feedback mechanism ensures smooth, sensor-driven control, applicable to tasks like object grasping in simulated environments.[25]
Best practices for Webots controllers emphasize proper time management and device handling to maintain simulation fidelity. Time synchronization is achieved by defining a TIME_STEP constant that aligns with the simulation's basic time step (e.g., 32 ms as a multiple of the default 16 ms), and calling the step function at this interval in the main loop to prevent desynchronization between controller execution and physics updates. Sensor sampling rates should match this time step when enabling devices via functions like wb_distance_sensor_enable(), ensuring consistent data without unnecessary computational overhead. For debugging, console output is facilitated by language-specific print statements—such as printf() in C or print() in Python—which Webots redirects to its console window, allowing real-time monitoring of variables like sensor readings; advanced users can include ANSI color codes from the Webots utilities library for enhanced visibility.[25]
Common pitfalls in controller programming include neglecting to enable sensors before reading them, which results in undefined or zero values and failed behaviors, as devices must be explicitly activated with an enable call specifying the sampling period. Another frequent error is omitting the simulation step in the loop, causing the controller to block indefinitely in synchronous mode or produce erratic results due to unadvanced physics; always include wb_robot_step() (or equivalent) to propagate changes and update the world state.[25]
Applications and Use Cases
Education and Research
Webots serves as a key tool in academic settings for teaching robotics fundamentals, offering beginner-friendly tutorials that guide users through robot modeling, simulation setup, and controller programming in C, with support for languages such as Python and C++.[50] These resources facilitate integration into university curricula, as seen in Carnegie Mellon University's "Robotics for Creative Practice" course, where Webots is employed to explore interdisciplinary projects combining art, engineering, and performance machines.[51] The simulator's guided tours and sample worlds further support structured learning in robotics courses worldwide, enabling students to experiment without physical hardware.[1]
In research, Webots supports algorithm development for complex scenarios, including swarm robotics, where particle swarm optimization has been simulated to coordinate collective behaviors among multiple robots.[52] Path planning techniques, such as A* algorithms for e-puck robots and deep reinforcement learning for aerial navigation in dense environments, are tested in Webots to validate efficiency and obstacle avoidance.[53] Machine learning applications, particularly deep reinforcement learning, benefit from frameworks like Deepbots, which streamline integration with Webots for training policies in simulated environments, reducing development overhead for researchers.[54]
Originating from EPFL projects in 1996, Webots has been utilized in institutional case studies, including contributions from EPFL's DISAL lab for enhancing simulator ergonomics in biologically inspired robotics.[55] As an EPFL spin-off, Cyberbotics has applied Webots in initiatives like the Human Brain Project for neuromechanical simulations and OpenDR for dexterous manipulation research.[1] Open-source extensions on GitHub allow researchers to customize nodes and controllers, fostering collaborative advancements since its commercialization in 1998.[4] Webots continues to be widely adopted in universities worldwide for such purposes.[1]
Webots provides a safe, cost-free platform for hypothesis testing, with deterministic physics ensuring reproducible experiments across multi-robot setups.[1] This reproducibility is crucial for validating research outcomes without real-world risks or expenses. The active community, including Discord channels for discussions and GitHub repositories for sharing student projects, enhances collaboration.[1] Webots also powers academic competitions, such as the RoboCup 2021 Virtual Humanoid Soccer, where teams simulate strategies in a standardized environment.[56]
Industrial and Commercial Applications
Webots has been adopted in various industrial sectors for prototyping, testing, and validating robotic systems, enabling companies to simulate complex environments without the immediate need for physical hardware. In the automotive industry, Webots supports the development of autonomous vehicle technologies through its dedicated "Webots for Automobiles" framework, which includes tools for importing OpenStreetMap data, integrating traffic simulations via SUMO, and modeling vehicle dynamics with realistic physics. For instance, Renault has utilized Webots to study driver reactions in simulated scenarios, while Perrone Robotics employs it for testing autonomous driving software in virtual urban settings.[1][57]
In manufacturing, Webots facilitates the simulation of collaborative robots for assembly line tasks, such as the Universal Robots UR3e, UR5e, and UR10e series, which are modeled with six degrees of freedom and integrated grippers like the ROBOTIQ 3F for pick-and-place operations. These models allow testing of motion planning with tools like MoveIt!, ensuring safe human-robot interactions in industrial environments. The UR models were developed with sponsorship from the ROSin European project, which aimed to enhance cross-platform ROS simulation for mobile manipulators, thereby supporting scalable deployment in factories.[58][59]
For aerial and aquatic applications, Webots enables validation of control systems in drones and unmanned surface vehicles (USVs). The Crazyflie quadrotor model, a lightweight 30-gram platform from Bitcraze, simulates indoor flight with PID control, GPS, and obstacle avoidance sensors, aiding commercial drone development for agile navigation tasks. Similarly, the Clearpath Heron USV model, introduced in Webots R2025a, supports simulation of marine operations like swarm coordination and ocean patrolling, with thruster dynamics and sensor fusion for COLREG-compliant path planning.[60][61]
Husarion's ROSbot, a four-wheeled autonomous mobile platform, is simulated in Webots for logistics and reconnaissance, featuring LIDAR, RGB-D cameras, and IMU for ROS2-based navigation and SLAM mapping in industrial warehouses. These integrations demonstrate Webots' role in accelerating iteration cycles by allowing rapid algorithm testing in photorealistic environments.[62][63]
Key benefits in commercial settings include reduced hardware prototyping costs through virtual validation and faster development via accurate physics simulation using the Open Dynamics Engine, which ensures compliance with real-world standards like collision detection and friction modeling. Additionally, its open-source nature under Apache 2.0 supports seamless integration with ROS and ROS2, facilitating deployment to hardware as detailed in cross-compilation guides.[9][64][1]
Included Robot Models
Mobile and Wheeled Robots
Webots includes a variety of pre-built models for mobile and wheeled robots, enabling users to simulate ground-based locomotion without building from scratch. These models support differential drive, all-terrain navigation, and advanced steering mechanisms, facilitating experiments in robotics education, research, and prototyping.[65]
Among the classic models, the e-puck is a miniature differential-drive robot originally developed at EPFL for educational purposes, featuring infrared proximity sensors for obstacle detection and eight wheels for stable movement.[66] The Pioneer 3-AT serves as an all-terrain four-wheeled platform suitable for outdoor applications like mapping and reconnaissance, equipped with a SICK LMS 291 laser rangefinder for precise distance measurement up to 80 meters (depending on object reflectivity).[67] Similarly, the Pioneer 3-DX is a two-wheeled indoor model with a caster wheel for maneuverability, supporting 16 sonar sensors (eight forward and eight rear-facing) for proximity sensing and LED indicators for status feedback.[68]
For educational use, the Khepera IV offers a modular two-wheeled design from K-Team, allowing sensor expansions such as a downward-facing camera for line following and eight infrared distance sensors for navigation.[69] The Thymio II is a low-cost, open-source differential-drive robot optimized for programming education, incorporating a suite of sensors including proximity, light, and ground detection alongside programmable LEDs and motors for interactive behaviors.[70]
Advanced models include the ROSbot from Husarion, a four-wheeled ROS-compatible platform designed for research in mapping and navigation, with support for ROS topics and services to integrate seamlessly with robotic operating systems.[71] Webots also provides demos for four-wheeled vehicles employing Ackermann steering geometry, where inner and outer wheels turn at different angles to minimize tire scrub during corners, as illustrated in sample worlds like four_wheels.wbt.[72]
Customization of these models is facilitated through PROTO files, which define reusable node hierarchies for modifying geometry, sensors, or actuators; for instance, users can adapt the e-puck's PROTO to add custom payloads. Demos such as keyboard-controlled driving allow real-time teleoperation of wheeled robots using simple controller scripts.[72]
In version R2022a, Webots introduced improvements to wheeled physics, including direct steering angle control via wbu_car_set_[right/left]_steering_angle functions and enhanced differential slip calculations for more realistic 4x4 vehicle dynamics.[73] Programming these models typically involves the Webots controller API for sensor data access and motor actuation, as explored in dedicated programming examples.
Aerial, Aquatic, and Humanoid Models
Webots provides a selection of pre-built models for aerial robots, enabling simulations of flight dynamics and control systems. The Crazyflie 2.1, a lightweight quadrotor developed by Bitcraze, is included as a representative aerial model with an integrated flight controller for realistic propeller-based propulsion and stability testing.[74] This model leverages Webots' physics engine to approximate aerodynamics, allowing users to experiment with hovering, trajectory following, and obstacle avoidance in 3D environments. A demo world demonstrates keyboard control for manual flight, facilitating quick prototyping of autonomous behaviors without hardware.[74]
For aquatic environments, Webots incorporates models suited to surface and underwater locomotion, emphasizing buoyancy and hydrodynamic interactions. The Heron USV, an unmanned surface vehicle from Clearpath Robotics, was added in version R2025a and features thruster-based navigation for simulating maritime tasks like patrolling or data collection on water surfaces.[7] Simple submarine prototypes are also supported through built-in buoyancy mechanisms, where users can assemble basic underwater vehicles using standard nodes for propellers and pressure sensors to model submersion and neutral buoyancy without requiring custom physics plugins. These aquatic models integrate with the simulator's fluid dynamics approximations to handle wave interactions and depth control, as briefly referenced in the physics simulation capabilities.
Humanoid models in Webots focus on bipedal and multi-joint mobility, supporting research in locomotion and manipulation. The Darwin-OP from Robotis is a compact bipedal humanoid with 20 degrees of freedom, calibrated for dynamic walking and balance simulations using inverse kinematics to generate stable gaits.[75] Similarly, the NAO robot from SoftBank Robotics (formerly Aldebaran) offers full-body motion models in versions V3.3, V4, and V5, with physics-tuned joints for tasks like stepping, arm reaching, and object interaction via inverse kinematics solvers.[76] Demo scenarios include pre-configured walking gaits for the Darwin-OP and NAO, showcasing periodic locomotion patterns that users can modify to study energy efficiency or terrain adaptation.[75][76]
Advanced Capabilities
ROS and ROS 2 Integration
Webots integrates with the Robot Operating System (ROS) frameworks to facilitate robotics development by allowing users to leverage ROS tools within simulated environments. For ROS 1, the webots_ros package provides interfaces that enable simulation of robots using standard ROS launch files, which start Webots worlds and controllers while mapping sensors and actuators to ROS topics and services, such as /clock for simulation time and /cmd_vel for velocity commands.[77] This package supports ROS Noetic, though it is deprecated as of R2025a due to the end-of-life of ROS 1 in May 2025, with continued access available via Docker images for legacy use.[16] Tools like urdf2webots assist in migrating models from Gazebo by importing URDF files into Webots, converting them to native PROTO formats for compatibility with ROS workflows.
ROS 2 integration is handled by the webots_ros2 package, which extends these capabilities to ROS 2 distributions including Humble, Iron (prior to R2025a), and Jazzy Jalisco, with Iron support dropped in the latest release to prioritize current versions.[16][78] Setup involves installing the package via APT repositories or building from source, followed by configuring launch files that spawn robots, publish sensor data (e.g., lidar scans via /scan or IMU via /imu), and subscribe to actuator controls, all using ROS 2 messages, services, and actions.[79] URDF import is supported natively, allowing models like the Universal Robots UR3e, UR5e, and UR10e to be loaded directly into Webots simulations with ROS 2 compatibility for topics like joint states and trajectories.[80]
Practical examples demonstrate the integration's versatility, such as using the ROS 2 navigation stack for path planning in simulated environments with differential-drive robots, where odometry and laser data feed into costmaps for obstacle avoidance.[79] SLAM simulations, like those with the SLAM Toolbox on models such as the ROSbot XL, enable map building from lidar and odometry inputs during exploration tasks.[81] Multi-robot coordination is achievable by launching multiple instances via parameterized launch files, allowing independent control over namespaces for topics like /robot1/cmd_vel and /robot2/scan in swarm scenarios.[78] These features bridge simulation and real hardware by reusing identical ROS 2 nodes and topics, streamlining development from virtual testing to physical deployment. Community-contributed packages on GitHub, such as those for specific robots like the Crazyflie drone with PID control plugins, further extend usability.[16][78]
Cross-Compilation and Remote Deployment
Webots supports cross-compilation of robot controllers to enable deployment on physical hardware with embedded processors, such as ARM-based microcontrollers. This process involves recompiling the controller code—written in languages like C, C++, Java, or Python—using the target robot's cross-compilation toolchain, allowing the code to run natively on the device without requiring a constant connection to a host computer.[82] For platforms like the e-puck robot, which uses an ARM7 processor, Webots provides integrated cross-compilation support, where users can build the controller binary directly from the simulator's build menu or terminal using predefined toolchains.[83] Similarly, for robots like the Khepera or Hemisson, custom include files and libraries are adapted to replace Webots' standard controller library, ensuring compatibility with the hardware's API.[82]
CMake is the primary build system in Webots for managing controller compilation, including cross-compilation setups. Users configure a CMakeLists.txt file in the controller directory, specifying include paths to Webots headers (e.g., $(WEBOTS_HOME)/include/controller/c) and linking against the appropriate controller libraries like libCppController. To target ARM architectures, such as those on Raspberry Pi or STM32 microcontrollers, a custom toolchain file is defined in CMake (e.g., specifying the ARM GCC cross-compiler path and sysroot), enabling builds for embedded Linux environments.[33] Once compiled, the resulting binary is exported from the controller directory and uploaded to the hardware via tools like scp for Raspberry Pi or manufacturer-specific programmers for STM32 devices.[34] Synchronization between simulation and hardware is achieved by calling wb_robot_step(duration) in the controller, where the duration parameter aligns execution steps with real-time factors, typically in milliseconds, to match the physical robot's timing.[49]
Remote deployment in Webots facilitates bridging simulations to physical robots by transferring sensor data and actuator commands over a network, primarily through TCP-based supervisor mode. In this mode, a supervisor controller—designated by setting the supervisor field to TRUE in the Robot node—uses the TCP/IP interface (e.g., via the tcpip controller example) to communicate with external software or hardware. The simulator can operate in synchronous mode, where it pauses until receiving commands like sensor readings or actuator updates, or asynchronous mode for higher throughput, with data exchanged via sockets on specified ports derived from the robot's name.[84] For hardware integration, the remote control plugin library wraps Webots API calls (e.g., wb_motor_set_position for actuators) into protocol-specific functions, initialized via wb_robot_set_mode(WB_MODE_REMOTE_CONTROL), enabling seamless redirection of I/O to the real robot over TCP or other protocols like Bluetooth.[85]
Webots.cloud extends remote deployment capabilities with browser-based simulation and execution, allowing users to run and edit worlds without local installation. This service hosts simulations in Docker containers on cloud GPU instances, supporting interactive 3D views, robot windows for control interfaces, and headless API calls for automated runs via GitHub repositories configured with webots.yml files.[35] For deployment workflows, users export simulation binaries or animations, upload them to the cloud, and synchronize with physical hardware by integrating cloud outputs (e.g., trajectories) into remote control sessions. Starting with release R2023b, a new launcher for extern controllers simplifies TCP connections and reconnection handling, improving reliability for distributed deployments.[31] These updates also bolster cross-compilation for embedded Linux, allowing controllers to be built and deployed directly to devices such as Raspberry Pi running ARM Linux distributions.[86]