Webots Reference Manual - chapter 3 - section 18

Webots Reference Manual


3.18 DifferentialWheels

Derived from Robot.

DifferentialWheels {
  SFFloat   motorConsumption    0      # [0,inf)
  SFFloat   axleLength          0.1    # (0,inf)
  SFFloat   wheelRadius         0.01   # (0,inf)
  SFFloat   maxSpeed            10     # (0,inf)
  SFFloat   maxAcceleration     10     
  SFFloat   speedUnit           1
  SFFloat   slipNoise           0.1    # [0,inf)
  SFFloat   encoderNoise        -1
  SFFloat   encoderResolution   -1
  SFFloat   maxForce            0.3    # (0,inf)
}

3.18.1 Description

The DifferentialWheels node can be used as base node to build robots with two wheels and differential steering. Any other type of robot (legged, humanoid, vehicle, etc.) needs to use Robot as base node.

A DifferentialWheels robot will automatically take control of its wheels if they are placed in the children field. The wheels must be Solid nodes, and they must be named "right wheel" and "left wheel". If the wheel objects are found, Webots will automatically make them rotate at the speed specified by the wb_differential_wheels_set_speed() function.

The origin of the robot coordinate system is the projection on the ground plane of the middle of the wheels' axle. The x axis is the axis of the wheel axle, y is the vertical axis and z is the axis pointing towards the rear of the robot (the front of the robot has negative z coordinates).

3.18.2 Field Summary

3.18.3 Simulation Modes

The DifferentialWheels's motion can be computed by different algorithms: "physics", "kinematics" or "Fast2D" depending on the structure of the world.

Physics mode

A DifferentialWheels is simulated in "physics" mode if it contains Physics nodes in its body and wheels. In this mode, the simulation is carried out by the ODE physics engine, and the robot's motion is caused by the friction forces generated by the contact of the wheels with the floor. The wheels can have any arbitrary shape (usually a cylinder), but their contact with the floor is necessary for the robot's motion. In "physics" mode the inertia, weight, etc. of the robot and wheels is simulated, so for example the robot will fall if you drop it. The friction is simulated with the Coulomb friction model, so a DifferentialWheels robot would slip on a wall with some friction coefficient that you can tune in the Physics nodes. The "physics" mode is the most realistic but also the slowest simulation mode.

Kinematics mode

When a DifferentialWheels does not have Physics nodes then it is simulated in "kinematics" mode. In the "kinematics" mode the robot's motion is calculated according to 2D kinematics algorithms and the collision detection is calculated with 3D algorithms. Friction is not simulated, so a DifferentialWheels does not actually require the contact of the wheels with the floor to move. Instead, its motion is controlled by a 2D kinematics algorithm using the axleLength, wheelRadius and maxAcceleration fields. Because friction is not simulated the DifferentialWheels will not slide on a wall or on another robot. The simulation will rather look as if obstacles (walls, robots, etc.) are very rough or harsh. However the robots can normally avoid to become blocked by changing direction, rotating the wheels backwards, etc. Unlike the "physics" mode, in the "kinematics" mode the gravity and other forces are not simulated therefore a DifferentialWheels robot will keep its initial elevation throughout the simulation.

Physics modeKinematics modeFast2D (Enki) mode
Motion triggered byWheels friction2d Webots kinematics2d Enki kinematics
Friction simulationYes, Coulomb modelNoYes, Enki model
Inertia/Weight/ForcesYesNoNo
Collision detection3D (ODE)3D (ODE)2D (Enki)
wheelRadius fieldIgnoredIgnoredUsed
axleLength fieldIgnoredIgnoredUsed
maxAcceleration fieldIgnoredIgnoredUsed
maxForce fieldUsedIgnoredIgnored
Sensor rays shape3d cone3d cone2d fan
RGB sensitiveYesYesNo

Table 3.2: DifferentialWheels simulation modes

Fast2D (Enki) mode

This mode is enabled when the string "enki" is specified in the WorldInfo.fast2d field. The "Fast2D" mode is implemented in a user-modifiable plugin which code can be found in this directory: webots/resources/projects/default/plugins/fast2d/enki. This is another implementation of 2D kinematics in which gravity, and other forces are also ignored simulated. However "Fast2D" mode the friction is simulated so a robot will smoothly slide over an obstacle or another robot. The "Fast2D" mode may be faster than "kinematics" in configurations where there are multiple DifferentialWheels with multiple DistanceSensors with multiple rays. However the "Fast2D" mode has severe limitations on the structure of the world and robots that it can simulate. More information on the "Fast2D" mode can be found here.

3.18.4 DifferentialWheels Functions



NAME

   wb_differential_wheels_set_speed - control the speed of the robot

SYNOPSIS [C++] [Java] [Python] [Matlab]

  #include <webots/differential_wheels.h>

  void wb_differential_wheels_set_speed(double left, double right);

DESCRIPTION

This function allows the user to specify a speed for the DifferentialWheels robot. This speed will be sent to the motors of the robot at the beginning of the next simulation step. The speed unit is defined by the speedUnit field of the DifferentialWheels node. The default value is 1 radians per seconds. Hence a speed value of 2 will make the wheel rotate at a speed of 2 radians per seconds. The linear speed of the robot can then be computed from the angular speed of each wheel, the wheel radius and the noise added. Both the wheel radius and the noise are documented in the DifferentialWheels node.



NAME

   wb_differential_wheels_enable_encoders, wb_differential_wheels_disable_encoders, wb_differential_wheels_get_encoders_sampling_period - enable or disable the incremental encoders of the robot wheels

SYNOPSIS [C++] [Java] [Python] [Matlab]

  #include <webots/differential_wheels.h>

  void wb_differential_wheels_enable_encoders(int ms);
  void wb_differential_wheels_disable_encoders();
  int wb_differential_wheels_get_encoders_sampling_period(WbDeviceTag tag);

DESCRIPTION

These functions allow the user to enable or disable the incremental wheel encoders for both wheels of the DifferentialWheels robot. Incremental encoders are counters that increment each time a wheel turns. The amount added to an incremental encoder is computed from the angle the wheel rotated and from the encoderResolution parameter of the DifferentialWheels node. Hence, if the encoderResolution is 100 and the wheel made a whole revolution, the corresponding encoder will have its value incremented by about 628. Please note that in a kinematic simulation (with no Physics node set) when a DifferentialWheels robot encounters an obstacle while trying to move forward, the wheels of the robot do not slip, hence the encoder values are not increased. This is very useful to detect that the robot has hit an obstacle. On the contrary, in a physics simulation (when the DifferentialWheels node and its children contain appropriate Physics nodes), the wheels may slip depending on their friction parameters and the force of the motors (maxForce parameter of the DifferentialWheels node). If a wheel slips, then its encoder values are modified according to its actual rotation, even though the robot doesn't move.

The wb_differential_wheels_get_encoders_sampling_period() function returns the period given into the wb_differential_wheels_enable_encoders() function, or 0 if the device is disabled.



NAME

   wb_differential_wheels_get_left_encoder, wb_differential_wheels_get_right_encoder, wb_differential_wheels_set_encoders - read or set the encoders of the robot wheels

SYNOPSIS [C++] [Java] [Python] [Matlab]

  #include <webots/differential_wheels.h>

  double wb_differential_wheels_get_left_encoder();
  double wb_differential_wheels_get_right_encoder();
  void wb_differential_wheels_set_encoders(double left, double right);

DESCRIPTION

These functions are used to read or set the values of the left and right encoders. The encoders must be enabled with wb_differential_wheels_enable_encoders(), so that the functions can read valid data. Additionally, the encoderNoise of the corresponding DifferentialWheels node should be positive. Setting the encoders' values will not make the wheels rotate to reach the specified value; instead, it will simply reset the encoders with the specified value.

release 7.0.2
Copyright © 2012 Cyberbotics Ltd. All right reserved.