Fact-checked by Grok 2 weeks ago

Webots

Webots is an open-source, multi-platform simulator that serves as a complete development environment for modeling, programming, and simulating robots, vehicles, and mechanical systems. Developed and maintained by Cyberbotics Ltd., a spin-off from the Swiss Federal Institute of Technology in (EPFL), Webots originated from research at the Laboratoire de Micro-Informatique (LAMI) and has been publicly available since 1998, becoming open-source in 2018. It supports Windows, , and macOS operating systems, enabling users to create realistic simulations with physics-based interactions, sensor modeling, and actuator controls. Key features of Webots include a modern built with , a customized fork of the () for physics simulation, and rendering capabilities powered by the Wren library using 3.3 for high-fidelity visuals. The simulator's application programming interface () is straightforward and supports programming in languages such as , , , , , and integration with the (), allowing for cross-compilation and of physical robots. Simulations can be exported as movies, interactive scenes, or real-time streams via and WebSockets, facilitating sharing and web-based demonstrations. Webots is widely adopted in , industry, and for tasks including algorithm prototyping, and development for , and educational training in control systems. 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 environments. The project's open-source nature, licensed under the 2.0 since 2018, encourages community contributions through its repository, while extensive documentation, tutorials, and testing ensure reliability and deterministic behavior in simulations.

Introduction

Overview

Webots is a free and open-source 3D robot simulator designed for modeling, programming, and simulating robots, vehicles, and mechanical systems. 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. Originally developed at the Swiss Federal Institute of Technology in (EPFL) in 1996, Webots has evolved into a versatile tool for applications. The simulator is widely used in , , and for and testing of robotic systems, including applications in , toy development, multi-agent coordination, and adaptive behaviors. Its physics-based simulation, powered by a fork of the (), allows for accurate modeling of , collisions, and environmental interactions. This makes it suitable for exploring complex scenarios without the need for physical hardware, reducing costs and risks in development cycles. Webots is beginner-friendly, offering intuitive tools and example models to introduce newcomers to concepts. It supports multiple platforms, including Windows, , and macOS, ensuring broad for users across different operating systems. The latest version, R2025a, was released on January 31, 2025, incorporating new features, improvements, and bug fixes to enhance simulation capabilities.

History and Development

Webots was initially designed in 1996 at the Laboratoire de Micro-Informatique (LAMI) of the Federal Institute of Technology in Lausanne (EPFL), , as a research tool for developing and testing mobile control algorithms. The project originated from efforts to create a flexible that allowed researchers to prototype robot behaviors without physical hardware. In 1998, Cyberbotics Ltd. was founded as a from EPFL by Olivier Michel, who transitioned Webots into a commercial product, marking the beginning of its proprietary development and sales phase. The company, based in , focused on enhancing the simulator's capabilities for professional use in and . This commercialization enabled broader adoption while sustaining ongoing improvements under a closed-source model for over two decades. 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. Since then, development has been hosted on , where Cyberbotics continues to lead enhancements supported by customer services, while inviting community contributions through pull requests and issue reporting. 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 from . R2022a, launched in December 2021, implemented major axis system changes, switching the global to ENU (East-North-Up) and object axes to FLU (Forward-Left-Up) for better compatibility with modern standards. R2023a, released in November 2022, incorporated the ROSbot from Husarion along with supporting device models like the MPU-9250 IMU. Most recently, R2025a in January 2025 introduced the USV model from and renamed the web scene format to W3D for streamlined workflows.

Core Features

Simulation Engine

Webots employs a customized fork of the () as its physics simulation backend, enabling accurate modeling of , , and joint constraints in robotic environments. This integration allows for realistic interactions such as forces, torques, and mass properties, with parameters like density, center of mass, and matrices passed directly to for computation. 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 rendering engine, a bespoke system built on 3.3 that provides high-fidelity graphics rendering. handles advanced features such as , physically-based rendering with () lighting, and real-time shadows, allowing users to observe detailed environmental and robotic behaviors without compromising simulation performance. 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. These modes facilitate multi-robot simulations, enabling scenarios with numerous interacting entities while maintaining computational efficiency. World construction leverages PROTO files, which encapsulate reusable node definitions for modular assembly of scenes, vehicles, or environments. Additionally, Webots imports assets from CAD-compatible formats like and DAE via the CadShape node, streamlining the integration of external geometries into the simulation. 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 modeled through coefficients in ContactProperties nodes, ranging from 0 (frictionless) to .

Supported Programming Languages and Platforms

Webots provides native support for Windows, distributions such as and , and macOS, operating on x86_64 architectures across all platforms and architectures on macOS via with compatibility where needed. This cross-platform compatibility enables developers to run simulations consistently across desktop environments without significant reconfiguration. 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. Additionally, external controllers can interface with Webots over TCP/IP for remote or third-party integrations, facilitating communication between the simulator and custom applications. 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. Webots includes a built-in compiler for C and C++ controllers, utilizing tools like on Windows and on , which streamlines the build process directly within the editor. It also integrates with external IDEs such as through Makefile configurations and community extensions, enabling advanced editing, debugging, and cross-compilation workflows, including (WSL) for hybrid development environments. For deployment, Webots allows exporting compiled controller binaries for standalone simulation execution without the full source codebase, supporting offline and distributed testing scenarios. Cloud-based simulations are enabled through webots.cloud, an open-source service for sharing interactive scenes, animations, and live streams accessible via web browsers.

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. 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. The 3D window, located at the center of the main interface, renders a real-time 3D representation of the simulated world using OpenGL. 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. Additional features include optional visualizations like contact points or lidar ray paths for debugging, accessible through the View menu. The Scene Tree, typically docked on the left side, presents a hierarchical of the world's structure, mirroring the VRML97-like organization including robots, solids, and environmental elements. Users can expand or collapse s to select and edit fields by double-clicking, with changes updating instantly in the ; right-clicking provides menus for actions like adding s or resetting fields. It serves as the primary entry point for world editing, such as modifying the basicTimeStep in the WorldInfo . The 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. Tailored for Webots controllers, it includes , auto-completion for functions, and buttons for building (compiling) and running the code directly within the . This window supports languages like , , Python, Java, and MATLAB, enabling quick iteration on controller logic without switching applications. The Console, positioned at the bottom or as a separate pane, captures output from runs, including errors (displayed in red), controller logs, and streams. Multiple consoles can be created via the for isolating outputs from different controllers, and they can be cleared individually or all at once to maintain clarity during . The spans the top of the with eight primary menus: for world and project operations (e.g., open, save, new); for standard editing actions; for display modes (e.g., wireframe, , ); for control actions (e.g., step, run, pause, mode); Build for controller ; Overlays for device visualizations; Tools for additional utilities such as the Tree visibility; and Help for access. Users can customize the , including language and startup mode, through the Preferences dialog accessible via the Tools .

Editing and Navigation Tools

Webots provides intuitive editing and navigation tools within its , enabling users to interactively modify the simulation environment. Selection of objects occurs by left-clicking on nodes in the window, which displays a bounding box with white lines outlining the object; pink lines indicate collision boundaries, while blue appears when idle. To select subparts of a , users hold the (or Alt+Ctrl on ) during clicking. Double-clicking a 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. Manipulation of selected objects uses bounding box handles for precise : users and axis-aligned handles to translate or rotate along specific directions. For freeform movement, holding Shift while left--dragging translates the object parallel to the , right--dragging rotates around the vertical , 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 ) and dragging with the left or right , simulating physical interactions during editing. is handled through the scale field in the node's Transform properties rather than direct handles. The Scene tree serves as the entry point for these operations, where nodes are selected and manipulated in a hierarchical view. Navigation in the 3D window relies on mouse interactions: left-click-dragging rotates the viewpoint around the , 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 . Restoring the initial view is done through "Restore Viewpoint," and predefined alignments like top or side views are accessible via the "Change View" . The main includes simulation controls such as play, pause, and a virtual time counter for stepping through animations, though no dedicated timeline slider is provided. 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., or ) enables editing via text input, for numeric adjustments, or checkboxes toggled with ; changes update the view immediately upon confirmation with Enter. Context menus in the window or Scene tree provide quick access to these tools for efficient workflow. 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. Import and export functionalities support interoperability with standard formats. Users import VRML97 (.wrl) or files via "File > " or the "Add > Import" dialog, converting them into Webots nodes for editing. Export options include saving worlds as VRML97 files ("File > Export VRML97") or for web integration, preserving and . Additionally, webots.cloud enables sharing of exported simulations online, allowing viewing in a without local .

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 and basic settings, serving as the foundational container for all other elements. 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. Central to robot modeling are the and nodes, which form the backbone of physical assemblies. The node acts as a container for devices and sub-components, featuring fields like boundingObject to specify collision and children to include subordinate nodes, such as positioning a as a child of a for hierarchical assembly. nodes, inheriting from the Pose node, represent tangible objects with fields for (defining visual and collision shapes) and physics (specifying , , and ), allowing precise placement and interaction within the . nodes, such as PositionSensor for detecting positions or Motor for actuation, are specialized extensions that must typically reside within a 's children field to integrate sensors and actuators into the robot's structure. 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 angles or thresholds. To enhance reusability, Webots supports nodes, which allow users to define custom, parameterized types as reusable templates, encapsulating complex assemblies like a standardized arm for repeated instantiation across worlds. For effective scene design, Webots employs DEF and USE mechanisms to promote modularity and efficiency. The DEF keyword assigns a to a instance, enabling its replication via USE , which avoids redundant definitions and supports instancing of identical components, such as multiple identical wheels in a model. Best practices emphasize shallow hierarchies to optimize 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.

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. 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. Rendering in Webots leverages the Wren engine, an 3.3 implementation supporting (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 coding. includes DirectionalLight for infinite sources like , PointLight for localized illumination with , and for focused beams, all contributing to shadow casting and when enabled. Atmospheric effects are added using the Fog node, which blends object colors toward a specified fogColor based on distance, with controlling exponential or linear fade rates for depth . 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. 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 preferences for texture quality (high/medium/low resolutions to cut GPU load), disabling shadows or (SMAA) for older hardware, and levels (medium/ultra) to balance quality and speed; culling is handled internally by to skip off-screen objects. Users can employ (LOD) through custom PROTO nodes grouping simplified geometries for distant views, though no built-in LOD node exists. Common issues like tunneling—where fast objects pass through solids—or arise from large time steps or stiff constraints, resolvable by reducing basicTimeStep to 16 ms or below for finer , increasing to 0.4-0.8 for better error correction, or lowering CFM to minimize drift; contact material tweaks, such as raising or , also prevent sinking or slipping without altering core solver iterations, which remain fixed in backend.

Controller Programming

API and Controller Structure

The Webots controller provides a structured interface for programming behaviors within the environment, enabling developers to interact with simulated sensors, actuators, and the overall state. The is designed to be where possible, with core functions available across supported languages, though explicit initialization and cleanup are primarily required in the API. This structure ensures deterministic control loops synchronized with the simulator's , facilitating real-time operation. 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 , setting up the necessary library resources; this step is essential in the C API but handled automatically in other bindings like . The main execution occurs in a loop calling wb_robot_step(duration), where duration specifies the time step in milliseconds—typically matching the worldInfo.basicTimeStep field for —and the returns -1 to signal 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. Key API categories encompass robot-level functions and device management. Robot functions include wb_robot_get_time(), which retrieves the elapsed time in seconds since the start, and wb_robot_get_mode(), which returns the current operating mode such as , , or mode to adapt controller logic accordingly. Device access is facilitated by wb_robot_get_device(name), which returns a to a named device like a or motor, allowing subsequent operations; can then be enabled with wb_device_enable(samplingPeriod) to start at specified intervals, and disabled with wb_device_disable() when no longer needed. 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 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 step. These operations ensure actuators influence the physics predictably. 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 or exchange in multi-robot scenarios. In supervisor mode—activated by setting the robot's field to TRUE—the extends to global simulation control, such as accessing other nodes or modifying the scene, though changes require reloading the world for persistence. Error handling in the API relies on return codes and 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. is managed through wb_robot_console_print(text, color), which outputs messages to the Webots console with optional color formatting for , or via standard output streams in non-C bindings, aiding in tracing controller execution without halting the .

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 . A basic example involves programming a simple wheeled 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 that steps the 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;
}
This approach ensures the maintains a constant forward velocity until the simulation ends or an external termination condition is met. Similar implementations exist in and , replacing C functions with object-oriented equivalents like Robot() and getDevice(), while preserving the initialization, setup, and stepping structure. For sensor-actuator interactions, an obstacle avoidance example uses to detect nearby objects and adjust motor velocities accordingly, implementing a reactive in a . In , the controller enables two , reads their values in each simulation step, and computes differential speeds to steer away from obstacles—for instance, turning right if the left 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)
This loop integrates and , with values typically ranging from 0 to 4095 based on proximity, allowing the to navigate dynamically without predefined paths. In multi-device scenarios, such as manipulating a , controllers coordinate s with motors to achieve precise movements, often using feedback loops for incremental ing. In , the program enables a on the , reads its current value in each step, and sets the motor to a slightly offset target 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
    }
  }
}
This feedback mechanism ensures smooth, sensor-driven control, applicable to tasks like object grasping in simulated environments. 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. 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.

Applications and Use Cases

Education and Research

Webots serves as a key tool in academic settings for teaching fundamentals, offering beginner-friendly tutorials that guide users through robot modeling, simulation setup, and controller programming in , with support for languages such as and C++. These resources facilitate integration into university curricula, as seen in Mellon University's "Robotics for Creative Practice" course, where Webots is employed to explore interdisciplinary projects combining , , and performance machines. The simulator's guided tours and sample worlds further support structured learning in courses worldwide, enabling students to experiment without physical hardware. In research, Webots supports algorithm development for complex scenarios, including , where has been simulated to coordinate collective behaviors among multiple robots. Path planning techniques, such as A* algorithms for e-puck robots and for aerial navigation in dense environments, are tested in Webots to validate efficiency and obstacle avoidance. applications, particularly , benefit from frameworks like Deepbots, which streamline integration with Webots for training policies in simulated environments, reducing development overhead for researchers. 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 . As an EPFL , Cyberbotics has applied Webots in initiatives like the for neuromechanical simulations and OpenDR for dexterous manipulation . Open-source extensions on allow researchers to customize nodes and controllers, fostering collaborative advancements since its commercialization in 1998. Webots continues to be widely adopted in universities worldwide for such purposes. Webots provides a safe, cost-free for testing, with deterministic physics ensuring reproducible experiments across multi-robot setups. This reproducibility is crucial for validating research outcomes without real-world risks or expenses. The active community, including channels for discussions and repositories for sharing student projects, enhances collaboration. Webots also powers academic competitions, such as the RoboCup 2021 Virtual Soccer, where teams simulate strategies in a standardized .

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 , Webots supports the development of autonomous vehicle technologies through its dedicated "Webots for Automobiles" framework, which includes tools for importing data, integrating traffic simulations via , and modeling with realistic physics. For instance, has utilized Webots to study driver reactions in simulated scenarios, while Perrone employs it for testing autonomous driving software in virtual urban settings. 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 and integrated grippers like the ROBOTIQ 3F for pick-and-place operations. These models allow testing of 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 for mobile manipulators, thereby supporting scalable deployment in factories. For aerial and aquatic applications, Webots enables validation of control systems in and unmanned surface vehicles (USVs). The Crazyflie quadrotor model, a lightweight 30-gram platform from Bitcraze, simulates indoor flight with control, GPS, and obstacle avoidance sensors, aiding commercial 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 for COLREG-compliant path planning. Husarion's ROSbot, a four-wheeled autonomous mobile platform, is simulated in Webots for logistics and reconnaissance, featuring , RGB-D cameras, and IMU for ROS2-based navigation and mapping in industrial warehouses. These integrations demonstrate Webots' role in accelerating iteration cycles by allowing rapid algorithm testing in photorealistic environments. Key benefits in commercial settings include reduced prototyping costs through virtual validation and faster development via accurate physics simulation using the , which ensures compliance with real-world standards like and modeling. Additionally, its open-source nature under Apache 2.0 supports seamless integration with ROS and ROS2, facilitating deployment to as detailed in cross-compilation guides.

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 , , and prototyping. 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. The Pioneer 3-AT serves as an all-terrain four-wheeled platform suitable for outdoor applications like mapping and reconnaissance, equipped with a LMS 291 for precise distance measurement up to 80 meters (depending on object reflectivity). Similarly, the Pioneer 3-DX is a two-wheeled indoor model with a caster wheel for maneuverability, supporting 16 sensors (eight forward and eight rear-facing) for proximity sensing and LED indicators for status feedback. 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. The Thymio II is a low-cost, open-source differential-drive optimized for , incorporating a suite of sensors including proximity, light, and ground detection alongside programmable LEDs and motors for interactive behaviors. 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. 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. 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 of wheeled robots using simple controller scripts. 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 . Programming these models typically involves the Webots controller 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 and control systems. The Crazyflie 2.1, a lightweight quadrotor developed by Bitcraze, is included as a representative aerial model with an integrated for realistic propeller-based propulsion and stability testing. This model leverages Webots' to approximate , 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. For aquatic environments, Webots incorporates models suited to surface and underwater locomotion, emphasizing and hydrodynamic interactions. USV, an from , was added in version R2025a and features thruster-based navigation for simulating maritime tasks like patrolling or on water surfaces. Simple submarine prototypes are also supported through built-in mechanisms, where users can assemble basic underwater vehicles using standard nodes for propellers and pressure sensors to model submersion and without requiring custom physics plugins. These aquatic models integrate with the simulator's 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. 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. 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.

Advanced Capabilities

ROS and ROS 2 Integration

Webots integrates with the (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. 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 images for legacy use. Tools like urdf2webots assist in migrating models from 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. 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. 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. 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. 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. 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. 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.

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. 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. 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. 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 architectures, such as those on or microcontrollers, a custom file is defined in (e.g., specifying the cross-compiler path and sysroot), enabling builds for embedded environments. Once compiled, the resulting binary is exported from the controller directory and uploaded to the hardware via tools like scp for or manufacturer-specific programmers for devices. 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. Remote deployment in Webots facilitates bridging simulations to physical robots by transferring data and commands over a , primarily through -based supervisor mode. In this mode, a controller—designated by setting the supervisor field to TRUE in the node—uses the / (e.g., via the tcpip controller example) to communicate with external software or . The simulator can operate in synchronous mode, where it pauses until receiving commands like readings or updates, or asynchronous mode for higher throughput, with data exchanged via sockets on specified ports derived from the robot's name. For integration, the library wraps Webots 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 or other protocols like . Webots.cloud extends remote deployment capabilities with browser-based and execution, allowing users to run and edit worlds without local . This service hosts simulations in containers on GPU instances, supporting interactive 3D views, robot windows for control interfaces, and headless API calls for automated runs via repositories configured with webots.yml files. For deployment workflows, users export simulation binaries or animations, upload them to the , and synchronize with physical by integrating outputs (e.g., trajectories) into sessions. Starting with release R2023b, a new launcher for extern controllers simplifies connections and reconnection handling, improving reliability for distributed deployments. These updates also bolster cross-compilation for embedded , allowing controllers to be built and deployed directly to devices such as running distributions.

References

  1. [1]
    Cyberbotics: Robotics simulation with Webots
    Webots is an open source and multi-platform desktop application used to simulate robots. It provides a complete development environment to model, program and ...Tutorials · Sample Webots Applications · Webots for Automobiles · Installing Webots
  2. [2]
    Webots User Guide
    The Webots software was initially developed at the Laboratoire de Micro-Informatique (LAMI) of the Swiss Federal Institute of Technology, Lausanne, Switzerland ...
  3. [3]
    Webots - Third-Party Products & Services - MATLAB & Simulink
    Webots is a free and open-source 3D robot simulator used in industry, education, and research ; Required Products. MATLAB ; Platforms. Linux; Macintosh; Windows ...
  4. [4]
    cyberbotics/webots: Webots Robot Simulator - GitHub
    Webots provides a complete development environment to model, program, and simulate robots, vehicles, and mechanical systems. It is a beginner friendly software ...<|control11|><|separator|>
  5. [5]
    Introduction to Webots
    Webots is a professional mobile robot simulation software package. It offers a rapid prototyping environment, that allows the user to create 3D virtual worlds.
  6. [6]
    ODE: Open Dynamics Engine - Webots documentation
    Webots relies on ODE, the Open Dynamics Engine, for physics simulation. Hence, some Webots parameters, structures or concepts refer to ODE.
  7. [7]
  8. [8]
  9. [9]
    [PDF] webots + ros - open-source robot simulation
    Mar 30, 2020 · 1996: Webots development started at EPFL, Lausanne, Switzerland. 1998: Founding of Cyberbotics Ltd. First sales of Webots licenses.
  10. [10]
    Cyberbotics Ltd. Webots™: Professional Mobile Robot Simulation
    was founded in 1998 as a spin-off company from the Swiss Federal Institute of Technology in Lausanne (EPFL). It currently employs two people and develops Webots ...
  11. [11]
    Olivier Michel | Opensource.com
    Feb 25, 2023 · In 1998, he founded Cyberbotics to continue the development of Webots and to commercialize it as a proprietary software. In 2018, Webots became ...Missing: history | Show results with:history
  12. [12]
  13. [13]
    Webots Blog: Version R2020b Released
    Jul 29, 2020 · Webots R2020b is there! And it's packed with a bunch of new features, new models, improvements and, of course, bug fixes.Version R2020b Released · 4 New Robot Models · Ros 2 & Webots
  14. [14]
    Webots Blog: Version R2022a Released
    Dec 21, 2021 · Today we're happy to announce the release of Webots R2022a! And it's packed with some new features, improvements and, of course, bug fixes.Version R2022a Released · Conversion To Flu/enu · Ros And Ros 2Missing: history | Show results with:history
  15. [15]
    Webots Blog: Version R2023a Released
    ### Summary of Webots R2023a Release
  16. [16]
    Webots Blog: Version R2025a Released
    ### Summary of Webots R2025a Release
  17. [17]
    Webots documentation: Physics
    The Physics node specifies the mass, the center of gravity and the mass distribution, thus allowing the physics engine to create a body and compute realistic ...Introduction of the Physics ...Physics
  18. [18]
  19. [19]
    Webots R2018b Changelog
    WREN: New Rendering System. Implemented a bespoke 3D graphics rendering engine based on OpenGL 3.3 from scratch. Implemented a Physically-Based Rendering ...Missing: details | Show results with:details
  20. [20]
    Webots documentation: The User Interface
    The Real-time menu item (and button) runs the simulation at real-time until it is interrupted by Pause or Step . In fast mode, the 3D display of the scene is ...The User Interface · File Menu · View MenuMissing: forward multi-
  21. [21]
    Supervisor - Webots documentation
    The simulation is paused. WB_SUPERVISOR_SIMULATION_MODE_REAL_TIME, The simulation is running as close as possible to the real-time.Missing: forward multi-
  22. [22]
    Web Streaming - Webots documentation
    Webots can be used as a Web streaming server, ie, to stream a simulation to several interactive 3D HTML pages, as shown in the figure below.Web Streaming · Description · Programming InterfaceMissing: fast- | Show results with:fast-<|separator|>
  23. [23]
    Tutorial 7: Your First PROTO (20 Minutes) - Webots
    The aim of this tutorial is to create a PROTO file corresponding to the four wheels robot from the previous tutorial.Missing: OBJ DAE
  24. [24]
    CadShape - Webots documentation
    The CadShape node renders a Collada (.dae) or Wavefront (.obj) object imported from an external file. Both Collada and Wavefront files can include 3D geometries ...Missing: building | Show results with:building
  25. [25]
    Controller Programming - Webots documentation
    The value 32 specifies the duration of the control steps, i.e., the wb_robot_step function shall compute 32 milliseconds of simulation and then return. This ...Controller Programming · Reading Sensors · Using Sensors And Actuators...Missing: friction | Show results with:friction
  26. [26]
    WorldInfo - Webots documentation
    The gravity field defines the gravitational acceleration along the vertical axis to be used in physics simulation. The gravity is set by default to the gravity ...Missing: ms coefficients
  27. [27]
    Webots documentation: ContactProperties
    ### Summary of Contact Materials for Friction and Restitution in Webots Physics
  28. [28]
    Installation Procedure - Webots documentation
    Webots will run on most recent Linux distributions running glibc2.11.1 or earlier. This includes fairly recent Ubuntu, Debian, Fedora, SuSE, RedHat, etc. Webots ...Installation Procedure · Installation On Linux · Installation On Macos
  29. [29]
    Programming Fundamentals - Webots documentation
    This chapter introduces the basic concepts of programming with Webots. Webots controllers can be written in C/C++, Java, Python or MATLAB TM.
  30. [30]
    Running Extern Robot Controllers - Webots documentation
    `ipc` should be used when Webots is running on the same machine as the extern controller. `tcp` should be used when connecting to a remote instance of Webots.Introduction · Usefulness · Launcher
  31. [31]
    Webots R2023 Change Log
    Jun 28, 2023 · Added support for any current and upcoming version of Python for robot controllers (#5297). Added new projection field to Camera, RangeFinder, ...
  32. [32]
    Webots documentation: Using C
    The Windows version of Webots comes with a pre-installed copy of the MinGW C/C++ compiler, so there is usually no need to install a separate compiler. The MinGW ...
  33. [33]
    Webots documentation: Using your IDE
    Webots works with any IDE to create, build and debug robot controllers. It is simply a matter of setting up the IDE correctly to use the build rules of Webots ...<|control11|><|separator|>
  34. [34]
    Compiling Controllers in a Terminal - Webots documentation
    It is possible to compile Webots controllers in a terminal instead of using the built-in editor. In this case you need to define the WEBOTS_HOME environment ...Missing: standalone | Show results with:standalone
  35. [35]
    Webots.cloud
    webots.cloud is an open-source webservice to share simulations online. You can share 3D scenes and animations recorded from a simulation, but also fully ...
  36. [36]
    Webots documentation: The 3D Window
    The 3D window allows selecting objects, navigating the scene by dragging the camera, and moving objects using axis-aligned handles or keyboard shortcuts.The 3d Window · Navigation In The Scene · Moving A Solid Object
  37. [37]
    Webots documentation: The Scene Tree
    ### Summary of the Scene Tree Description
  38. [38]
    Webots Built-in Editor
    The Source Code Editor can be used to compile C/C++ or Java source files into binary executable or bytecode (Java) files that can be executed in a simulation.
  39. [39]
    Preferences - Webots documentation
    The Startup mode allows you to choose the state of the simulation when Webots is started (pause, realtime, run, fast; see the Simulation menu). The Editor ...Preferences · General · OpenglMissing: real- time forward multi-
  40. [40]
    Webots documentation: W3D and Web Scene
    When the export is completed, Webots will ask to playback the resulting file in the default Web browser. Note: The CSS file, the W3D file and the required ...Missing: timeline | Show results with:timeline
  41. [41]
    Node Chart - Webots documentation
    The Webots Node Chart outlines all nodes for building worlds, showing inheritance, abstract nodes, and bounding objects. Arrows show inheritance, and dashed ...
  42. [42]
    Webots documentation: Nodes and Keywords
    Webots uses a subset of VRML97 nodes, adds specialized nodes for robotic experiments, and has reserved keywords that cannot be used in DEF or PROTO names.
  43. [43]
    Webots documentation: Solid
    A Solid node represents an object with physical properties, dimensions, contact material, and optionally mass. It's the base for collision-detected objects.Solid · Field Summary · How To Use The...Missing: aids axis indicators
  44. [44]
  45. [45]
    Webots documentation: HingeJoint
    ### Summary of HingeJoint in Webots Physics Simulation
  46. [46]
  47. [47]
    Light - Webots documentation
    Lights have two purposes in Webots: (1) the are used to graphically illuminate objects and (2) they determine the quantity of light perceived by LightSensor ...Light · Description · Field Summary
  48. [48]
    Fog - Webots documentation
    The Fog node provides a way to simulate atmospheric effects by blending objects with the color specified by the color field based on the distances of the ...Missing: shaders | Show results with:shaders
  49. [49]
    Webots documentation: Robot
    The Robot node can be used as basis for building a robot, eg, an articulated robot, a humanoid robot, a wheeled robot.Robot · Wb_robot_cleanup · Field SummaryMissing: forward | Show results with:forward
  50. [50]
    Tutorials - Webots documentation
    The aim of this chapter is to explain the fundamental concepts of Webots required to create your own simulations. Learning is focused on the modeling of robots ...
  51. [51]
    Webots Robot Simulator — Robotics for Creative Practice - Fall 2025
    Webots is an open source robot simulator available from Cyberbotics, available for macOS, Windows, and several versions of Ubuntu Linux. It supports multi-robot ...
  52. [52]
  53. [53]
    Simulation of e-puck path planning in webots - ResearchGate
    Aug 7, 2025 · This paper details simulation of an e-puck robot platform running an A* path planning algorithm using the Webots development environment.
  54. [54]
    Deepbots: A Webots-Based Deep Reinforcement Learning ... - NIH
    Deepbots aims to enable researchers to easily develop DRL methods in Webots by handling all the low-level details and reducing the required development effort.
  55. [55]
    DISAL's Contributions to the Design and Development of the Webots ...
    In 2005 and 2006 the Webots contribution was sponsored by the Fond d'Innovation pour l'Education (FIFO) at the EPFL. The objective of the FIFO grant was to ...
  56. [56]
  57. [57]
    Webots for Automobiles
    This manual is provided on an as-is basis. Neither the copyright holder nor any applicable licensor will be liable for any incidental or consequential damages.Driver Library · OpenStreetMap Importer · SUMO Interface · WorldsMissing: demo | Show results with:demo
  58. [58]
    Universal Robots UR3e, UR5e and UR10e - Webots
    The Universal Robots UR3e, UR5e and UR10e are flexible collaborative robot arms with 6 degrees of freedom. The Universal Robots UR3e, UR5e and UR10e models ...
  59. [59]
  60. [60]
    Bitcraze's Crazyflie - Webots documentation
    The Crazyflie is a smalll 30 gram quadcopter developed by Bitcraze. Index. Movie Presentation; Crazyflie Proto; Samples. crazyflie.wbt. Movie Presentation.Missing: Heron USV
  61. [61]
  62. [62]
    Webots documentation: Husarion's ROSbot
    ### Summary of Husarion ROSbot and Commercial Applications
  63. [63]
  64. [64]
  65. [65]
  66. [66]
    Webots documentation: GCTronic' e-puck
    E-puck is a miniature mobile robot originally developed at EPFL for teaching purposes by the designers of the successful Khepera robot.Gctronic' E-Puck · Overview Of The Robot · Control InterfaceMissing: pre- | Show results with:pre-
  67. [67]
    Adept's Pioneer 3-AT - Webots documentation
    The Pioneer 3-AT robot is an all-purpose outdoor base, used for research and prototyping applications involving mapping, navigation, monitoring, reconnaissance ...Adept's Pioneer 3-At · Pioneer 3-At Model · Pioneer3at ProtoMissing: pre- | Show results with:pre-
  68. [68]
    Webots documentation: Adept's Pioneer 3-DX
    This model includes support for two motors, the caster wheel, 7 LEDs on the control panel and 16 sonar sensors (8 forward-facing, 8 rear-facing) for proximity ...Adept's Pioneer 3-Dx · Pioneer 3-Dx Model · Pioneer3dx Proto
  69. [69]
    K-Team's Khepera IV - Webots documentation
    The "Khepera IV" robot is a two-wheeled robot produced by K-Team. It is mounted by multiple sensors including 8 distance sensors. Index. Movie Presentation ...
  70. [70]
  71. [71]
    Husarion's ROSbot - Webots documentation
    The ROSbot is a ROS-powered four-wheeled robot with 4x4 drive, 4 infra-red sensors, a LIDAR, an RGB-D camera, and an IMU, used for research.
  72. [72]
    Webots documentation: How To
    This example shows three models of four-wheeled vehicles. In the first ... In the third layout, a simple Ackermann steering geometry is shown. Note ...
  73. [73]
    Webots R2022 Change Log
    Sep 13, 2022 · Improved the user experience when using the object rotation around axis feature (#3540). Increased the mouse wheel speed when zooming the 3D ...
  74. [74]
  75. [75]
  76. [76]
  77. [77]
    cyberbotics/webots_ros: Webots ROS package - GitHub
    The webots_ros package contains examples for interfacing ROS nodes with the standard ROS controller of Webots. How to set-up the ROS interface in Webots:.
  78. [78]
    cyberbotics/webots_ros2: Webots ROS 2 packages - GitHub
    webots_ros2 is a package that provides the necessary interfaces to simulate a robot in the Webots open-source 3D robots simulator. It integrates with ROS2 ...
  79. [79]
    Webots — ROS 2 Documentation: Humble documentation
    This set of tutorials will teach you how to configure the Webots simulator with ROS 2. Installation (Ubuntu) · Installation (Windows) · Installation (macOS) ...
  80. [80]
    Cyberbotics: doc
    **Summary:**
  81. [81]
    Webots: ROSbot XL + SLAM Toolbox + Navigation2 - Husarion
    This guide demonstrates how to run the ROSbot XL simulation in Webots, create a map of the unknown world using the Slam Toolbox and deploy autonomous ...
  82. [82]
    Transfer to your own Robot - Webots documentation
    Once linked with your own remote control plugin, you can control your real robot by running the simulation in Webots. It might be useful to also add a robot ...Transfer To Your Own Robot · Remote Control · Cross-CompilationMissing: hardware | Show results with:hardware
  83. [83]
    Cyberbotics: doc
    Insufficient relevant content. The provided URL (https://cyberbotics.com/doc/guide/epuck) returns a "404: Not Found" error, and the content snippet only includes a page not found message and a link to contribute on GitHub. No information about the e-puck robot model in Webots is available.
  84. [84]
    Interfacing Webots to Third Party Software with TCP/IP
    Webots comes with an example of interfacing a simulated Khepera robot via TCP/IP to any third party program able to read from and write to a TCP/IP connection.Missing: external | Show results with:external
  85. [85]
    Webots documentation: Controller Plugin
    The main purpose of a remote-control library is to wrap all the Webots API functions used by the robot with a protocol communicating to the real robot.
  86. [86]
    System Requirements - Webots documentation
    An NVIDIA or AMD OpenGL (minimum version 3.3) capable graphics adapter with at least 512 MB of RAM is required. We do not recommend any other graphics adapters, ...Missing: Wren | Show results with:Wren