Abstract

An easier method for the calibration of differential drive robots is presented. Most calibration is done on-board and it is not necessary to spend too much time taking note of the robot’s position. The calibration method does not need a large free space to perform the tests. The bigger space is merely in a straight line, which is easy to find. The results with the method presented are compared with those from UMB for reference, and they show very little deviation while the proposed calibration is much simpler.

1. Introduction

The massive development of open hardware, single on-board microcontrollers has increased research on low cost robotic platforms. These kinds of robots are subject to increased interest in fields such as collective robotics [1, 2] or educational approaches [3, 4], where a new philosophy, known as minimalism, used created robots (UCR), in which the concepts of simplicity and low cost concepts converge. Simple differential drive robots (DDR) are designed with a special emphasis in the absence of expensive or complex components.

Our research group has been working on developing many different technical aids within the Padrino Tecnológico philanthropic program, ranging from walkers to electric wheelchairs. We have found that there is a huge need for technical aids for assistive tasks, but the focus on low cost must be considered when developing those aids. Orientation for people with cognitive disorders is essential, and helping to increase their autonomy is the primary goal of this project, although many other functionalities can be included using the same hardware. The proposed solution is also based on a DDR that shares the paradigms of simplicity and low cost with the fields mentioned above. The sensors used in all the platforms described, besides wheel encoders, involve short distance sensors such as bump sensors, IR, or long distance sensors based on ultrasonics but the latter do not have a high level of precision due to the low cost restriction.

Robot calibration is a process by which robot positioning accuracy can be improved by modifying the robot positioning software, instead of changing or altering the design of the robot or its control system [5]. This process can be undertaken easily if precision exteroceptive sensors are present, such as LIDAR [6], sonar or depth sensor [7, 8], and cameras [9, 10]. Many studies have proposed calibration methods for industrial robots [1114]. Localization of the robot, and therefore calibration, can also be based on active or passive beacons, but this kind of solution is not always possible in nonlaboratory or industrial environments. Some studies have developed a calibration method for DDR based mainly on laser range finder sensors [1517]. In the context discussed here, with an absence of precise long range sensors, odometry based on encoder information is the main source of information for localization. Long range sensors can be present and, in fact, we use them in the method proposed, but we cannot rely on the measures they provide when calibrating the odometry. Having a good calibration based on encoder information is also useful for a more complex DDR, as it avoids systematic errors and facilitates the fusion with other sources of localization information.

Although some studies have considered the problem, we introduce in this paper a novel and simple method that does not require a great deal of effort when preparing the scenario, or too much time spent annotating positions. It only requires a free 3 m line of space, which is easily available in most scenarios. The paper is structured as follows: the mathematical expressions are introduced in Section 1.1 and there is a detailed description of the published works that have studied the calibration based on odometry from encoder sensors in Section 1.2.

1.1. Odometry Calculations

By way of a summary, we have included the odometry expressions for differential robots, in order to highlight the dependency of those calculations on the parameters we need to calibrate. Iteratively, the position of the robot is obtained by approximation. For a given iteration, and represent the pulses of the right and left encoder, respectively.

The factor that converts the pulses into mm of linear displacement is , given by where is the wheel’s diameter and is the number of pulses per revolution of our encoder. In each iteration , the distance travelled by the right and left wheels is therefore The distance travelled by the centre of the wheel axis and the change in the orientation in each iteration are given by where is the wheelbase: the distance from the contact point of both wheels to the floor. The global orientation is And finally, the estimated position of the robot for iteration is As can be seen in these equations, they depend on and , where will be and because of the two wheels.

1.2. Related Work

After an introduction of the main parameters to be adjusted, it is easier to describe other published works based on odometry.

References [18, 19] are the main references for systematic odometry error correction. In [18], a 4 m sided square is travelled clockwise and counterclockwise in order to correct the ratio of the wheel diameters and the distance between the wheels.

There are 3 sources of error. First, in the average wheel diameter , we consider a scaling factor from the nominal value. Second, it is a fact that the wheel diameters are unequal. This error can vary depending on the construction of the wheel. If we take the diameter of the right wheel as a reference, the left diameter is given by the factor : The last error source to adjust is the wheelbase, , so that the relation between the actual wheelbase, , and the nominal is Some papers have proposed correcting and [18, 20]. For example, in [21], the 3 parameters are adjusted.

Two experiments are described in [21]: a movement forward with a rotation of and then a coming backwards movement, one with a clockwise rotation and one counterclockwise. Simulation results are provided, but they do not state the number of iterations of the experiments. In [18], travelling across a 4 m side square both counterclockwise and clockwise, 5 times each, is discussed. One of the problems is that free space of 4 m 4 m, plus the dimensions of the robot, is required, as well as a regular nonslippery floor. They also assumed , so needs to be calibrated before starting the experiments. The robot must be placed carefully in the same position and orientation for the 10 trials. In [22], the expressions from [18] are corrected. The effect of the square path size is also examined: 1 m 1 m was not successful, because it was too small. In simulation, their expressions show better convergence if the experiment is iterated and better results for 2 m 2 m. In [20] a bidirectional circular path test is proposed to estimate the correction factors. These authors discuss a circular path 5 m in diameter, which is even worse than the 4 m square recommended in [18]. In [23] two factors, longitudinal and lateral, are used but the paper starts with the assumption that the differences in the wheel radii are known.

We are seeking a method for occasional calibration that requires little time. It is important to note that the referenced studies need a space which, despite being easy to find in a research laboratory, is not able in most end user locations. The proposed method needs just enough space for the robot to turn and to perform a 3 m long straight movement. It is also important to note that most of the data for the calibration are obtained and calculated on-board. No care is required with the initial position of the robot. These features enable the robot to be calibrated very quickly.

2. Calibration Method

2.1. Automatic Whole Round Detection

Before describing the calibration method for each of the parameters, we outline how the method also includes a process to automatically detect when a whole round has been completed. This is done in order to allow a nonqualified person to be able to calibrate the robot without taking into account if the round has been completed or not. This automatic whole round detection is based on a module of ultrasound sensors (HC-SR04).The measuring range of this sensor is 2cm-2m, and it is connected to a 5V power source.

At this point it is important to emphasize that the accuracy of the ultrasounds distance measurements is not important, but instead the profile of the received measurements when the robot is turning around. The most important issue is therefore that the scenario must not be “periodic” or the obstacles found should not be uniform. Let us name the sequence of distance values obtained from the ultrasound sensor , with being the number of pulses read from the encoder, when the robot has exceeded one round. The length of the signal will be noted as , and so, the autocorrelation function will have a length of and can be defined as

where and are the start and end point, respectively, of a window around and where is the theoretical number of pulses that the robot needs to complete one turn, obtained from and . will then reflect the actual number of pulses to complete a whole round. In our case, we have selected and to have a window of pulses. Figure 6 and the zoomed Figure 7 show the distances from the sensor as a function of the pulses of the encoder of the moving wheel. It is apparent that the distances measured in the peaks are not equal and we are not even interested in the extent of error in the real distance to the obstacles. What we are truly interested in is the autocorrelation of the sequence that can estimate when the robot has completed a round. Figure 8 shows the autocorrelation for the distances read from the ultrasound sensor, showing where the peak is located, which gives the point in the sequence that corresponds to a whole round.

This method avoids errors in the annotation of the pulses per round. In fact, the robot turns around for several laps, and the pulses are annotated automatically, obtaining and .

2.2. Estimation of

The proposed calibration method aims to reduce the time required to perform a calibration. We are seeking the actual , , and . The first experiment looks for the relation : the robot will describe a circular path with the left wheel stopped for rounds. This is then repeated with the right wheel stopped for another rounds. Figure 1 shows the robot while turning with a stopped left wheel. The distance travelled, , in each round, can be expressed in different ways depending on the effective wheelbase and the number of pulses in each round and :where, as mentioned above, pulses/rev is a constant to translate wheel turns to pulses.

Using Equation (10) yields

The movements involved in this test suffer from one problem: stopped wheels need low levels of friction to perform the circular movement of the robot but enough friction to take the wheel to the same point. When the test is done on a slippery floor, a small piece (see Figure 2) has been designed to achieve this goal, so that now the wheel pivots on that piece over an axial bearing. Figure 3 illustrates the situation of the wheel during the test: the wheel, the piece, and the axial bearing are visible.

The incorporation of this small piece implies that the distance travelled not only is based on the effective wheelbase, but also depends on the height of the piece. We can consider that the distance travelled is where is the distance from the point of contact between the piece and the floor to the point of contact with the opposite wheel (the wheel that is the one not stopped). Nevertheless, as the same piece is located first under one wheel and subsequently on the other, the distance per lap is going to be the same, and equation (11) holds.

2.3. Estimation of

The robot’s movements while attempting to travel in a straight line are illustrated in Figure 4. The actual distance from A to B is not the output of the encoder corrected by the conversion factor . However, if the robot’s orientation is kept below a given threshold, the maximum deviation of that measurement can be controlled. For example, if the orientation remains below , then the maximum deviation remains less than 0.02%, and, for , less than 0.06%. Those deviations can be accepted for our experiments and we will analyze the robot’s orientation to reject the measurements where the maximum deviation of orientation is greater than a given threshold.

The right wheel is taken as a reference, and is corrected by the factor . In the second experiment, a straight motion for 3 m is performed by the robot, and the number of pulses of the right wheel, , with the actual distance travelled gives the conversion factor from pulses to mm as The actual is given byand, in our case, pulses/rev.

is obtained by means of and :Returning to Equation (9) and taking into account that a small piece was introduced the value of is given byWe are interested in obtaining . To that end, we performed a movement turning over one stopped wheel and then turning with both wheels at the same speed but in opposite directions, taking into account the number of pulses required to complete a turn with the stopped wheel and the number of pulses when turning with the two wheels at the same speed . The factor to obtain is

3. Experiments

In this section, we present one of the experiments to provide a better understanding of the method involved and how the parameters are obtained. UMB calibration was also used to compare our method with the most popular one used to calibrate differential robots without highly accurate distance sensors. Our robot software has 3 parameters to adjust. They are set before starting each calibration method:

3.1. UAH Calibration 1

The first experiment was carried out with the robot platform shown in Figure 5. First, with the left wheel stopped, the robot performed a given number of rounds and the experiment was then repeated for a stopped right wheel.

Figure 6 shows the output of the ultrasound sensor for 9 turns and only two periods are plotted in Figure 7. It is important to ensure that the scenario is not symmetrical in order to get the proper period. In our case, because of the limited sensor range of 2 metres, the scenario must not be too large.

The number of pulses when the left wheel is stopped per turn (period) is for three iterations, and as can be seen, the variance for different iterations is low. When the right wheel is stopped, is also for three iterations of the experiment.

We then obtained the effective wheelbase factor for movements with a stopped wheel, so the robot performed movements as was explained previously. We obtained pulses and pulses, so

Several iterations of these experiments were carried out, and the raw data for 5 experiments of each can be found at http://agamenon.tsc.uah.es/Investigacion/gram/papers/Sensors/Results.zip.

Taking the mean value

In order to perform the second experiment, the factor must be included in the robot’s odometry, so we set up the new in the robot software or automatically update it if the calculation is done on-board.

A 3m long motion is then performed and the number of pulses in several iterations is illustrated in Table 1, where the number of pulses for the distance actually travelled gives the factor . The maximum deviation in orientation is also considered in order to discard results with deviations more than .

From the results in Table 1 we obtain mm/pulse.

The wheelbase distance can be obtained from and the can be calculated using the value found above: which gives, mm, from Equation (13) mm and from Equation (14) , where the used nominal diameter was mm and the new average of the diameters is mm. We do not use but it will be necessary to perform a calibration from [18] for comparison.

3.2. UMB Calibration

The from UAH calibration 1 is used to perform the UBM calibration [18]. The setup parameters are

The UMB method [18] was carried out for a square of m (as was suggested in [22]) for 5 rounds clockwise and 5 counterclockwise, and the final point deviations of each movement were recorded. Our robot platform is almost 1 m long and a larger free scenario was not viable.

The results for the error centres of gravity for clockwise (, ) and counterclockwise rounds (, ) are where the error is the difference between the actual absolute position of the robot and the calculated position.

Using the equations from [18], in degrees, the results above give and in degrees, , so mm and .

If the correction from [22] is included, a slight change is obtained: mm.

4. Validation

In [18], the same experiment used for calibration is repeated after calibration in order to test the method. This validation process needs a large space to perform the test. In [20, 21], only simulation results are presented to compare the methods.

In order to test the results of calibration, the journey involved travelling along a 3 m long path, followed by a turn through an angle of and then returning for 3 m. These experiments were repeated thirty times to obtain statistical conclusions. Tables 2 and 3 show the error in mm in the and coordinates and in radians for the orientation before calibration, with the calibration method UAH and for UMBmark. The error in Table 2 is basically due to the error in the wheel diameters and the error in Table 3 is affected by the wheel diameters and .

Figure 9 shows the error before calibration, with the UMB method calibration and the method proposed in this paper (UAH). Because of the simplicity of our method, we used it instead of the UMB. Most of the measurements in the method proposed herein are done on-board, and the initial point is not important in most of the movements.

5. Conclusions

The paper presents a new method for differential drive robot calibration. One of its main contributions is that the free space needed to perform the calibration in our method is very small. Furthermore, only one manual measurement is required with our method, which can be repeated in order to check the correctness, but checking the maximum orientation makes discarding wrong measurements easy. The most complicated part of the calibration method can be done on-board. If a calibrated distance sensor is available, the whole method can be implemented on-board.

Our results are very close to those obtained with the UMB method, so we use our method because of its simplicity in performing the calibration.

Future work will focus on extending the method discussed here to nondifferential robots, while emphasising the low-cost design. A study of Ackerman-type or multiwheel traction robots will therefore be performed to enable a simple autocalibration method without any space restrictions, as presented in this study.

Low-cost camera odometry and the method proposed here are also an interesting research line. This means that, once the encoder odometry has been calibrated, the visual odometry from low-cost cameras can be joined to feed back the whole system.

Data Availability

http://agamenon.tsc.uah.es/Investigacion/gram/papers/Sensors/Results.zip includes all the data and instructions to verify or replicate the experiments to other researchers.

Conflicts of Interest

The authors declare that they have no conflicts of interest.

Acknowledgments

This work was partially supported by the University of Alcalá research programme with projects CCG2016/EXP-045 and CCG2016/EXP-042 and by the project PREPEATE, with reference TEC2016-80326-R, of the Spanish Ministry of Economy, Industry and Competitiveness.