3.18 DifferentialWheels
Derived from Robot.
DifferentialWheels { |
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
-
motorConsumption: power consumption of the the motor in Watts.
-
axleLength: distance between the two wheels (in meters). This field must be specified for "kinematics" based robot models. It will be ignored by "physics" based models.
-
wheelRadius: radius of the wheels (in meters). Both wheels must have the same radius. This field must be specified for "kinematics" based robot models. It will be ignored by "physics" based models.
-
maxSpeed: maximum speed of the wheels, expressed in rad/s.
-
maxAcceleration: maximum acceleration of the wheels, expressed in rad/s2. It is used only in "kinematics" mode.
-
speedUnit: defines the unit used in the wb_differential_wheels_set_speed() function, expressed in rad/s.
-
slipNoise: slip noise added to each move expressed in percent. If the value is 0.1, a noise component of +/- 10 percent is added to the command for each simulation step. The noise is, of course, different for each wheel. The noise has a uniform distribution, also known as as "white noise."
-
encoderNoise: white noise added to the incremental encoders. If the value is -1, the encoders are not simulated. If the value is 0, encoders are simulated without noise. Otherwise a cumulative uniform noise is added to encoder values. At every simulation step, an increase value is computed for each encoder. Then, a random uniform noise is applied to this increase value before it is added to the encoder value. This random noise is computed in the same way as the slip noise (see above). When the robot encounters an obstacle, and if no physics simulation is used, the robot wheels do not slip, hence the encoder values are not incremented. This is very useful to detect that a robot has hit an obstacle. For each wheel, the angular velocity is affected by the slipNoise field. The angular speed is used to compute the rotation of the wheel for a basic time step (by default 32 ms). The wheel is actually rotated by this amount. This amount is then affected by the encoderNoise (if any). This means that a noise is added to the amount of rotation in a similar way as with the slipNoise. Finally, this amount is multiplied by the encoderResolution (see below) and used to increment the encoder value, which can be read by the controller program.
-
encoderResolution: defines the number of encoder increments per radian of the wheel. An encoderResolution of 100 will make the encoders increment their value by (approximately) 628 each time the wheel makes a complete revolution. The -1 default value means that the encoder functionality is disabled as with encoderNoise.
-
maxForce: defines the maximum torque used by the robot to rotate each wheel in a "physics" based simulation. It corresponds to the dParamFMax parameter of an ODE hinge joint. It is ignored in "kinematics" based simulations.
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 mode | Kinematics mode | Fast2D (Enki) mode | |
| Motion triggered by | Wheels friction | 2d Webots kinematics | 2d Enki kinematics |
| Friction simulation | Yes, Coulomb model | No | Yes, Enki model |
| Inertia/Weight/Forces | Yes | No | No |
| Collision detection | 3D (ODE) | 3D (ODE) | 2D (Enki) |
| wheelRadius field | Ignored | Ignored | Used |
| axleLength field | Ignored | Ignored | Used |
| maxAcceleration field | Ignored | Ignored | Used |
| maxForce field | Used | Ignored | Ignored |
| Sensor rays shape | 3d cone | 3d cone | 2d fan |
| RGB sensitive | Yes | Yes | No |
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 robotSYNOPSIS [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 wheelsSYNOPSIS [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 wheelsSYNOPSIS [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.