| ![]() |
2.3 DifferentialWheelsdifferential_wheels_set_speeddifferential_wheels_enable_encoders, differential_wheels_disable_encoders differential_wheels_get_left_encoder, differential_wheels_get_right_encoder, differential_wheels_set_encoders differential_wheels_set_speedNAMEdifferential_wheels_set_speed -- control the speed of the robotSYNOPSIS#include <device/differential_wheels.h>void differential_wheels_set_speed(gint16 left, gint16 right); DESCRIPTIONThis function allows the user to specify a speed for the differentially wheeled robot. This speed will be send 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 0.1 radian per seconds. Hence a speed value of 20 will make the wheel rotate at a speed of 2 radian 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 on the command. Both the wheel radius and the noise on the command are documented in the DifferentialWheels node. differential_wheels_enable_encodersNAMEdifferential_wheels_enable_encoders, differential_wheels_disable_encoders -- enable or disable the incremental encoders of the robot wheelsSYNOPSIS#include <device/differential_wheels.h>void differential_wheels_enable_encoders(guint16 ms); void differential_wheels_disable_encoders (void); DESCRIPTIONThese functions allow the user to enable or disable the incremental wheel encoders for both wheels of the DifferentialWheels robot. Incremental encoder are counters that incremented each time a wheel turns with the value of the speed for the corresponding wheel. For example, if you set a speed of 400 for the left wheel and perform a robot step of 64 ms, the left encoder will increase its value of 400 * 0.064 = 25.6 after this step. However, if the initial value of the encoder was 0, the value you will read will be 25 and not 25.6. But if you repeat the same step, the computed value will be 51.2 and you will be able to read 51. Please note that when the DifferentialWheels robot faces 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. differential_wheels_get_left_encoderNAMEdifferential_wheels_get_left_encoder, differential_wheels_get_right_encoder, differential_wheels_set_encoders -- read or set the encoders of the robot wheelsSYNOPSIS#include <device/differential_wheels.h>gint32 differential_wheels_get_left_encoder (void); gint32 differential_wheels_get_right_encoder (void); void differential_wheels_set_encoders (gint32 left, gint32 right); DESCRIPTIONThese functions are used to read or set the values of the left and right encoders. The encoders have to be enabled with differential_wheels_enable_encoders, so that the functions can read correct values. Moreover, the encoderNoise of the corresponding DifferentialWheels node should be positive. Setting encoders value will not make the wheels rotate to reach the specified value, instead, it will simply reset the encoders with the specified value. ![]() ![]() ![]() ^ page top ^ |
E-mail to webmaster | Last updated: | Copyright © 2002 Cyberbotics Ltd. |