Keywords

1 Introduction

Inertial sensors are based on inertia. Normally, this classification refers to gyroscope and accelerometer sensors. The first one measures the angular velocity, i.e., the rate of change of sensor’s orientation, while the second one provides the external specific force acting on the sensor, which corresponds to its acceleration plus the earth’s gravity [7]. These elements are, typically, arranged together on an inertial measurement unit (IMU). A triad of accelerometers and a triad of gyroscopes (one sensor per axis) are comprised inside, complemented, in some units, with a triad of magnetometers, which indicate local magnetic field, fulfilling a set of tri-axial clusters [14]. Traditionally, its use became popular on military applications, being, nowadays, exploited to industrial purposes, namely robot navigation systems as well as body motion tracking, and also included on smartphones. For such tasks, an IMU is based on microelectro mechanical systems (MEMS), characterized for being small, light and low power consumption [7].

The downside of using low cost MEMS based IMU is that, usually, they are associated to calibration issues, including non accurate scaling, sensor axis misalignment, cross-axis sensitivities and non-zero biases [14]. These are related with imperfections in production process [15]. Additionally, the presence of magnetic perturbations largely degrades magnetometers’ performance. That’s why, a reliable operation implies a previous calibration, which consists in identifying the enumerated parameters [14]. Some manufactures provide products calibrated by default and with increased accuracy. However, such procedures cost time and resources, enriching, naturally, the unit value, invalidating a cost-effective utilization [15].

Despite of a good calibration, sensors’ output is still noisy and can’t be directly used to provide position, velocity and orientation estimations, increasingly differing from the true value along time. This is a problem commonly addressed on literature. The solution depends on the necessary application accuracy. While with relaxed constraints a low pass filter in each sensor set of samples is enough [3], for tracking problems, fusion of IMU sensors is mandatory to obtain a reliable estimation. With that in mind, there are complementary filter based algorithms and Kalman filter approaches [7]. In this paper, the sensor information is combined through a Kalman filter implementation. Depending on processing capability, there are some IMU that already provide filtered samples due to internal algorithms supported on cited approaches. This feature is associated with higher cost units.

The purpose of this paper is to evaluate distinct IMU performance over a proposed comparison procedure. The strategy followed is to take different cost range products, proceed to calibration and posterior samples filtration, checking whether in the end the results have the same accuracy or if, in fact, the manufacturing quality limits it.

To achieve such goal, in next subsection, it is exposed the calibration techniques and filter implementations presented in literature, being followed by the details about the chosen approach for both processing stages. Next, the tests performed are referred. First, the setup configuration supporting those is detailed and, then, the results are shown, evaluated and compared among IMU. Here, three models are tested – UM7 from CHRobotics (an average price of $140), MinIMU-9 v3 from Pololu (an average price of $15) and 10 DOF IMU from Waveshare (also an average price of $15) – being later detailed. Last, some conclusions and further improvements are suggested.

1.1 Related Work and Contributions

The IMU calibration is a problem massively referred in the literature. Although calibrated IMUs are commercially available, they not always represent the best solution, namely with respect to size, flexibility and cost criteria [4]. In some cases, it is preferable a tailor made (allowing to pick some specific models of inertial sensors) or cheaper units, introducing, however, the need of calibration.

The basic idea consists in comparing the sensors’ output with the reference value and use that to quantify error model parameters. The traditional methods are based on precision centrifuge tests [5], optical [6] and GPS trackers [8], which provides a ground truth for linear acceleration and/or angular rate. Since calibration parameters are characterized by slowly time variance, in [13] is also suggested an extended Kalman filter implementation to achieve an online estimation of bias and axes’ misalignment. However, all these procedures not only imply an external infrastructure to act as reference, which has an inherent high cost, as well as treat the sensors as independent entities, ignoring the cross-misalignment between sensors’ frames. Those drawbacks are overpassed in [14] proposing a multi-position calibration procedure (which can be even made by hand) and taking advantage of an optimization algorithm to calculate sensors’ model. This is the work that supports this paper. The approach, however, lacks in the fact that doesn’t include the magnetometer calibration and can be complemented by the work [12]. Here, the magnetometer calibration is a two step process: the first one related with sensor model using earth magnetic field as reference and, then, the alignment with the remaining sensors’ coordinate system. Additionally, in [9], a similar approach to [14] is promoted but using a robotic arm to a better trajectory precision. This is only valid if the motion between positions is slow enough to ignore the linear acceleration regarding to gravity.

Even after calibration, sensors measurements tend to be accurate, but just for a short time, suffering from integration drift over longer time scales [7]. Such behavior makes impossible to obtain a reliable estimation in tracking applications. The solution is to combine all inertial information from sensors. Most of resources in the literature points to the use of Kalman filters (KF) or the extended version (EKF) [11]. To decrease algorithm complexity, a typical approach is to decompose the estimation in two stages, separating position from orientation. In the last one, the quaternions are the preferable choice to represent rotations, for being compact, singularity free and easily converted from or to rotation matrix and Euler angles [10]. In [7], an EKF implementation is proposed, using, in the prediction step, a constant acceleration model and a constant angular velocity model. The approach fuses information from all sensors and provides a reliable representation of system model, but uses different ways of representing rotations (mixing quaternions with rotation matrices), requiring online calculation of several large size matrices which aren’t of easy deduction. To overcome the computational demand, a simplified EKF implementation is presented in [2]. Here, the processing effort is transferred to an external algorithm that extracts the quaternion from inertial sensors samples, role which might be performed by TRIAD method. This is an algebraic algorithm that obtains the direction cosine matrix (DCM) relating two frames, requiring a pair of vectors in one of them and the respective counterpart in the other one (for further detailed explanation see [1]). For all said, this paper provides a solution that merges both approaches. As additional feature, it is included a magnetometer validation module that, in each iteration, evaluates the conditions to discard or not the sensor sample. According to [11], those conditions are related to the angle between accelerometer and magnetometer measurements (which must be constant in absence of movement or in a constant velocity trajectory) and sensed magnetic field norm (which must be also constant and equal to earth field one, in the absence of disturbances).

2 Calibration

The calibration of sensors consists in identifying the systematic error’s sources, the consequent sensor error model and quantify its parameters. The acquired samples are, then, corrected using the calculated model. The procedure flow of the present topic is the following: the accelerometer is calibrated taking gravity as reference, the gyroscope is calibrated using accelerometer corrected samples as reference and then the magnetometer is calibrated using both earth magnetic field and accelerometer samples as reference.

2.1 Accelerometer and Gyroscope

The accelerometer and gyroscope calibration is supported and implemented by [14].

First, we need to identify the error’s sources and in what way they affect sensor’s output. In case of inertial sensors, the samples are dominated by instrumentation errors. Assembling imperfections are included in this group. Those are caused by bad sensors disposition on IMU frame in a way that they are not orthogonal with each other, as supposed. Thus, they represent an invalid coordinate system. In addition, it isn’t guaranteed that the coordinate systems from different sensors match. Therefore, all the frames must be aligned to a reference one, being selected the corrected accelerometer orthogonal frame. Then, the gyroscopes’ coordinate system must be aligned with that. To simplify the problem, it is assumed that the reference frame matches the IMU body frame. Mathematically, the compensation consists in samples multiplication by a square matrix (T) where \(\alpha \) and \(\beta \) represent the angular displacement between accelerometer (a) and gyroscope (\(\omega \)) axes, respectively.

$$\begin{aligned} T^a = \begin{bmatrix} 1 &{}&{} -\alpha _{yz} &{}&{} \alpha _{zy}\\ 0 &{}&{} 1 &{}&{} -\alpha _{zx}\\ 0 &{}&{} 0 &{}&{} 1 \end{bmatrix}&T^\omega = \begin{bmatrix} 1 &{}&{} -\beta _{yz} &{}&{} \beta _{zy}\\ \beta _{xz} &{}&{} 1 &{}&{} -\beta _{zx}\\ -\beta _{xy} &{}&{} \beta _{yx} &{}&{} 1 \end{bmatrix} \end{aligned}$$
(1)

Besides that, the measurements may also include scale factors (s) distortions, compensated by a diagonal matrix (K).

$$\begin{aligned} K^a = \begin{bmatrix} s^a_x &{}&{} 0 &{}&{} 0\\ 0 &{}&{} s^a_y &{}&{} 0\\ 0 &{}&{} 0 &{}&{} s^a_z \end{bmatrix}&K^\omega = \begin{bmatrix} s^\omega _x &{}&{} 0 &{}&{} 0\\ 0 &{}&{} s^\omega _y &{}&{} 0\\ 0 &{}&{} 0 &{}&{} s^\omega _z \end{bmatrix} \end{aligned}$$
(2)

Finally, there are additive errors. They emerge as an offset value on sensors’ output, tending to diverge over long time runs as well as between turn on operations. They are classified as bias (b).

The accelerometer and gyroscope calibration models are given, respectively, by 3 and 4. The superscript o refers to calibrated sample on orthogonal frame while s refers to non-calibrated sample provided by sensor.

$$\begin{aligned} \overrightarrow{a}^o = T^aK^a(\overrightarrow{a}^s+\overrightarrow{b}^a+\overrightarrow{v}^a) \end{aligned}$$
(3)
$$\begin{aligned} \overrightarrow{\omega }^o = T^\omega K^\omega (\overrightarrow{\omega }^s+\overrightarrow{b}^\omega +\overrightarrow{v}^\omega ) \end{aligned}$$
(4)

The v parameter refers to white noise (gaussian with zero mean) that is removed through Kalman filter, presented in next stage.

The model parameters quantification is made by a minimization algorithm. Its input is the set of samples acquired during a multi-position calibration path [14]. Shortly, the IMU is moved along several positions, remaining static, during a some time, in each one. To assure the posterior convergence of the algorithm, it is recommended a number of positions between 36 and 50 and to stay, at least, 5s in each one. The referred movement can be performed manually, i.e., just by hand, but, to increase results accuracy, the tests described in this work were realized with a robotic arm.

The acquired accelerometer samples are the input of the minimization function, which is formulated as the reference value minus sensor model output (L). In this case, gravity corresponds to the reference (g) but only if linear acceleration is discarded, which is only valid when the IMU rests at static positions or performs a constant linear velocity movement. That’s why, only that samples’ subset (of size M) is used on minimization algorithm, which is an implementation of Levenberg-Marquardt method [14].

$$\begin{aligned} L(T^a, K^a, b^a) = \sum _{k=1}^{M} \big ( \Vert \overrightarrow{g}\Vert _2 - \left\| T^aK^a(\overrightarrow{a}^s_k+b^a) \right\| _2 \big )^2 \end{aligned}$$
(5)

Regarding to gyroscope, the implementation follows the same guidelines. However, since during static positions the angular rate is zero, the angular integration (function \(\psi \)) occurs on transitions instead. Here, the calibrated accelerometer samples are used to extract the reference, which is the angular displacement between the samples immediately before and after the transition interval (\(u_{a}\)). Similarly to accelerometer calibration, a minimization function is also defined (L).

$$\begin{aligned} L(T^\omega , K^\omega , b^\omega ) = \sum _{k=1}^{N} \left\| u_{a,k} - \psi (T^\omega ,K^\omega , b^\omega , \omega ^s_k, u_{a,k-1}) \right\| _2 \end{aligned}$$
(6)

2.2 Magnetometer

In magnetometers, besides the previous instrumental errors, their measurements are also susceptible to magnetic perturbations. In an ideal scenario, the magnetometer should only measures earth’s magnetic field. However, when applied indoors, local magnetic fields tend to overlap it. Such effects may be classified as hard and soft irons. The first ones are characteristic of some materials that generate their own magnetic field, actuating equally in all directions/axes. On the other side, the soft irons result from materials that perturb earth’s field but in specific directions of actuation.

To exemplify the concepts exposed, three scenarios are now considered. In absence of any distortion, when the IMU is rotated on a space plane, a circumference is drawn from magnetometer samples, centered at IMU body and with a radius equal to earth’s magnetic field norm. In presence of hard irons perturbations, a circumference is still obtained but translated from center and with a different radius value. Finally, the soft irons presence generates an ellipse, centered at the origin, and with the respective axes indicating the direction of the distortion.

The compensation of previous effects is made over two steps. Since hard irons induce an offset on the measurements, the same value must be subtracted to the data (\(H^m\)). On the other hand, to transform an ellipse into a circumference, their axes must be aligned with body frame axes (\(R^m\)), apply a scale factor (\(S^m\)) per axis and turn back to initial orientation (\(R^{m^{-1}}\)). The resulting sensor model is presented in Eq. 7.

$$\begin{aligned} \overrightarrow{m}' = (R^{m^{-1}}S^mR^m\overrightarrow{m}^s-\overrightarrow{H}^m) \end{aligned}$$
(7)

In addition, it must be also considered the instrumentation errors already referred. In order to simplify the final model, some simplifications are performed, concentrating the calibration parameters only in two matrices (A, B).

$$\begin{aligned} \overrightarrow{m}^o = T^mK^m(\overrightarrow{m}'+\overrightarrow{b}^m+\overrightarrow{v}^m) = A(\overrightarrow{m}^s + \overrightarrow{B} + \overrightarrow{v}^m) \end{aligned}$$
(8)

The calibration procedure is made over two moments. In the first step, the IMU must be forced to describe circumference based paths (at least one per space’s plane) and the magnetometer samples must be recorded. Such measurements are the input of the minimization algorithm, already used in previous sensors. The reference is the earth’s magnetic field vector in that point of the globe (\(\overrightarrow{m}^{ref}\)).

$$\begin{aligned} L(A,B) = \sum _{k=1}^{M} \big (\Vert \overrightarrow{m}^{ref}\Vert _2 - \Vert \overrightarrow{m}^o_k\Vert _2 \big )^2 \end{aligned}$$
(9)

In this point, the calculated model already represents the calibrated samples relatively to the magnetometer orthogonal frame. However, it is still necessary to align this coordinate system with the other sensors. For that, the accelerometer frame is used as reference and the constant angle between both sensors’ arrays is included as a problem restriction. Once again, this is a minimization problem to find the rotation that minimizes the angular displacement between samples. Such rotation could be represented by a rotation matrix, but would be a 9-parameter problem and would imply the consideration of SO(3) properties. To avoid that computational effort, the axe-angle representation is preferred, reducing the solution to only three parameters. The minimization algorithm follows the previous implementation rules. The samples used as input are the ones acquired during multi-position path: the calibrated accelerometer measurements (the output of 3) and magnetometer samples on orthogonal frame (the output of 8).

Considering the constant angle between samples, the unitary norm arrays and taking advantage of inner product properties results in Eq. 10.

$$\begin{aligned} \frac{\overrightarrow{a} \cdot \overrightarrow{b}}{\Vert a\Vert \Vert b\Vert } = cos(\overrightarrow{a},\overrightarrow{b}) \end{aligned}$$
(10)

Finally, the problem formulation is presented in Eq. 11, being a the accelerometer calibrated sample and m the magnetometer orthogonal sample (output of 8). The goal is to obtain a rotation (given by \(\omega \) in axis-angle representation) which closes as much as possible the sample’s angular displacement from real angular displacement between gravity and earth’s magnetic field (\(\alpha \)).

$$\begin{aligned} argmin_{\overrightarrow{\omega }} \sum _{i=1}^{n} \big (\overrightarrow{a^o}^T_i \cdot Rot(\overrightarrow{\omega }) \overrightarrow{m}_{i}^{o} - cos(\frac{\pi }{2} - \alpha )\big )^2 \end{aligned}$$
(11)

3 Kalman Filter

According with the ideas captured from literature and presented in Sect. 1, the Kalman filter implementation is divided in two subsystems: position and orientation estimation. Although some cross-effects are lost, this decision is justified by the reduction of complexity.

Regarding to linear motion, the main goal is to estimate the position (p), linear velocity (v) and acceleration (a) in 3D space. Inspired in [7], it is defined a constant linear acceleration motion model (where linear acceleration corresponds to Kalman filter state, x), being the remaining estimations obtained by pure integration during sampling time (T). The system has only one output (y) which is the linear acceleration on body frame (obtained by rotation from earth to IMU frame, \(R^{bn}\)), the output of inverse accelerometer model calibrated on previous stage.

$$\begin{aligned} p_{t+1} = p_t + Tv_{t} + \frac{T^2}{2}a_{t} \end{aligned}$$
(12)
$$\begin{aligned} v_{t+1} = v_{t} + Ta_{t} \end{aligned}$$
(13)
$$\begin{aligned} x_{t+1} = a_{t+1} = a_{t} + e_{a,t} \end{aligned}$$
(14)
$$\begin{aligned} y_{t} = (T^{a}K^a)^{-1}R_{t}^{bn}(a_{t} + g^n) - b_a + e_{a,t} \end{aligned}$$
(15)

In terms of orientation, it is intended to obtain quaternion and angular velocity estimations. The quaternion is given by time integration, according with the angular displacement in each iteration (which is angular velocity integrated during sampling time, T). The angular velocity is directly replaced by the calibrated value of gyroscope measure (\(\omega ^o\)). A constant angular velocity model could be considered instead, but it would be accomplished by computational complexity with the advantage of the estimation being less sensitive to perturbations. With this implementation, although more reactive, a better commitment is achieved. The system state and output are the same, the quaternion that represents the rotation from IMU to earth frame (\(q^{nb}\)). The observation quaternion is returned by the application of TRIAD method over the set of accelerometer (\(a^o\)) and magnetometer (\(m^o\)) calibrated samples and gravity and earth magnetic filed arrays. Taking the two pair of arrays, the algorithm returns the rotation matrix that best relates the earth and IMU frames, being, after that, converted to quaternion representation which constitutes the observation measure.

$$\begin{aligned} x_{t+1} = q_{t+1}^{nb} = q_t^{nb} + \frac{dq_t^{nb}}{dt}T + e_{q,t} = q_t^{nb} + \frac{1}{2}\varOmega (\omega ^o) q_t^{nb} + e_{q,t} = \end{aligned}$$
(16)
$$\begin{aligned} \begin{bmatrix} 1 &{}&{} -0.5T\omega _x^o &{}&{} -0.5T\omega _y^o &{}&{} -0.5T\omega _z^o \\ 0.5T\omega _x^o &{}&{} 1 &{}&{} 0.5T\omega _z^o &{}&{} -0.5T\omega _y^o \\ 0.5T\omega _y^o &{}&{} -0.5T\omega _x^o &{}&{} 1 &{}&{} 0.5T\omega _x^o \\ 0.5T\omega _z^o &{}&{} 0.5T\omega _y^o &{}&{} -0.5T\omega _x^o &{}&{} 1 \\ \end{bmatrix} \cdot q_t^{nb} + e_{q,t} \end{aligned}$$
(17)
$$\begin{aligned} y_{t} = q_{meas,t}^{nb}(a^o, m^o) = q_t^{nb} + e_{q_m,t} \end{aligned}$$
(18)
$$\begin{aligned} \omega ^o = T^{\omega }K^\omega (\omega ^{s} + b^{\omega }) \end{aligned}$$
(19)
$$\begin{aligned} a^o = T^aK^a(a^{s} + b^a) \end{aligned}$$
(20)
$$\begin{aligned} m^o = A^m(m^{s} + b^m) \end{aligned}$$
(21)

3.1 Magnetometer Validation

During the movement of IMU, it could interact with a magnetic neighborhood, generating perturbed magnetometer measurements. In such scenarios, the sample is not valid and must be discarded, otherwise an unreliable estimate would be provided. The validation must be performed in each iteration, before applying Kalman filter, and through two verification steps. First, it is calculated the magnetometer array norm (\(\overrightarrow{m}_k\)) and verified if that is within a established acceptance range (\(\epsilon _m\)). Second, if the first condition is verified with success, the inclination angle, i.e., the angle between the array and the horizontal plane, is considered ((\(\epsilon _{dip}\))). A set of samples is considered valid when it passes with success over the two tests.

$$\begin{aligned} \left| \Vert \overrightarrow{m}_k\Vert - \Vert \overrightarrow{h}\Vert \right|<\epsilon _m \quad \cap \quad \left| \varTheta _{dip} - arccos(\frac{R^{nb}\overrightarrow{m}^o \cdot R^{nb}\overrightarrow{a}^o}{\Vert \overrightarrow{m}^o\Vert \Vert \overrightarrow{a}^o\Vert }) \right| < \epsilon _{dip} \end{aligned}$$
(22)

When the samples are rejected, there is no valid magnetometer sample and the TRIAD method is not applied on that iteration. Instead, an Euler angles representation is applicable: the roll and pitch angles are extracted from accelerometer samples and the yaw is extracted from predicted quaternion of prediction step. In the end, a transformation from Euler angles to quaternions form is applied.

3.2 Allan Variance

The sensors model parameters tend to be characteristics of a specific IMU. However, the bias, namely from the gyroscope, tend to slowly varies with time when in operation. That’s why, since such parameters are considered static on filter model, during long time runs they can become outdated and not correctly reproduce the initial calibrated model. To avoid that, it is important to calculate instability of the sensors and, that way, know during how long the model is valid according to acceptable tolerance. That value can be obtained through the Allan variance calculation. This is a mathematical tool which provides the stability degree of a set of samples along the time. Since we are looking for low frequency variations, the samples should be acquired during a large time interval (8 hours and above) and in static conditions, i.e., with the sensor immobilized. The minimum value of the graphic indicates the maximum stability in degrees per second and, with the maximum angular tolerance allowed, the validity of the model is easily extracted.

In addition, this parameter can be used as a benchmarking indication to compare different sensors. How much lower is the (in)stability, the sensor operation is more precise during a long interval operation whereby it is suggested that it has a more quality construction, providing an immediate choice criteria of IMUs without any further test.

4 Results

4.1 Setup and Methodology

The objective of tests is to compare the performance of different IMUs, with distinct construction quality, and to conclude whether this premise affects or not the accuracy of the estimation, even after calibration and filtering of the measured samples. For that purpose, three units were picked from different cost ranges. They were UM-7 from CHRobtics, minIMU-9 v3 from Polulu and 10DOF IMU v2 from Waveshare. All units offer a triad of 3-axis accelerometers, gyroscopes and magnetometers.

For all of them, raw data was collected, and pros-processing done offline.

The tests were carried out over three trajectories. It was defined, in first place, a calibration path, characterized by a circumference based movement in each plane of 3D space (xy, xz, yz) in order to ensure the large number of positions required to the calibration algorithm convergence. Although this trajectory allows to evaluate the position and orientation tracking, the movements were considered, separately, on a square (with a fixed orientation) and circular paths.

To be able to simulate the indicated motions multiple times and always with equal spaced points in the trajectory, an ABB IRB2600 was used (see Fig. 1. The paths’ design was, firstly, supported on a simulated environment, RobotStudio, and, only then, transferred to real world application.

Additionally, a 3D printed tool was built to remove the magnetic perturbations produced by having the IMus and the end-effort’s metallic material in close proximity and to ensure a proper accommodation.

Fig. 1.
figure 1

ABB IRB2600 and 3D printed end-effort tool used in the tests.

4.2 Experimental Results

To process the results, the samples were converted from raw data to proper units (g, rad/s and gauss) and only then were able to be compared with the reference. Here, it was used the position and orientation feedback provided by the robotic arm, with an enough accuracy to be considered, in this case, the ground truth. The comparison criteria was the root mean square error. Such indicator was computed (per coordinate error and Euler angle error) before and after calibration and after Kalman filter application in order to observe the estimation increments induced. After, an inter-IMU analysis is carried out, discussing the final accuracy of each unit. The referred procedure was developed in each configured path.

$$\begin{aligned} e_{rms} = \sqrt{\frac{1}{N} \sum _{i=1}^Ne_i^2} \end{aligned}$$
(23)

Calibration Trajectory. Resuming what was previously said, the trajectory path is formed by a large number of positions where the IMU rest during, approximately, 10 s. The trajectory points are included in different planes of 3D space.

Regarding to orientation, this is represented in quaternions format. However, since its components don’t provide an intuitive error’s interpretation, the Euler angles representation is applied. Then, the root mean square error is showed on Table 1.

Table 1. Root mean square orientation error of the IMUs.

The purpose of showed results is to present the improvement introduced by calibration procedure and justify its use. This is applied over the three IMUs. In no calibration case, the samples are directly used to calculate the orientation estimation and then compared with the reference returned by robotic arm, being the result exported on Euler angles format. The same samples are, then, corrected through calibrated sensors’ error model and the orientation calculated again. In both cases, the Kalman filter is not considered. For UM7, it can be seen that, even without any correction, the samples have an acceptable orientation error, with an equivalent precision in all axes. Since calibration algorithm can’t provide more accurate measures, its application degrades the estimated angles. Regarding to remaining units, the calibration effect is more noticeable. With minIMU, the most yelling improvement is imputed to yaw angle, which might be justified by an initial deficient magnetometer calibration, while accelerometer provide reasonable measures (used to obtain roll and pitch). Finally, with 10DOF unit, the calibration need is more explicit. The improvement is shared by all angles, indicating, probably, a worst manufacturing quality construction, inherent to both accelerometer and magnetometer.

The calibration intends to eliminate the systematic errors, while the subsequent Kalman filter has the purpose to suppress the zero mean noise which affects the samples. This process results in a smooth and more precise estimation when compared with calibration data, also due to the inclusion of magnetometer validation module. The 10DOF IMU case is presented in Fig. 2.

Fig. 2.
figure 2

10DOF calibrated and filtered quaternions comparison.

In terms of position tracking, a more detailed analysis is made in square trajectory topic.

Angular Trajectory. This path is characterized by an axial movement perpendicular to horizontal earth’s plane. There is no end-effort translation, staying rotating on a fixed point until it reaches the joint limit, alternating between clockwise and anticlockwise. The root mean square error of Euler angles is discriminated on Table 2, being considered the filtered values.

Considering all angles, it is concluded that the UM7 present the best behaviour, being the error more noticeable only in yaw (the axis direction of the movement). Regarding to minIMU, an equivalent precision was achieved, being the 10DOF the worst unit. This result can be partially justified by the fact of the rotation’s speed be higher than sample rate of sensors, making difficult the tracking task.

Table 2. Root mean square orientation error on circular path.

Square Trajectory. Despite of already has been concluded that the units are unable to track a linear displacement, it is, anyway, provided a procedure to evaluate such capability. Since the path is described by a robotic arm, the available working area is more restricted. For that reason, it was defined a square path, in xy plane, with 50 cm of side length. It was performed several turns.

The filtered position estimation diverges continuously from robot reference since initial moment. Such behaviour is common to all axes, being justified by the fact that estimate results from time integration of calibrated linear acceleration and, that’s why, any offset from real value will affect position estimation by a quadratic factor, leading to an unbounded estimation error.

To compensate that behaviour, it is proposed the definition of reference positions which provide a reset of position estimation always they were crossed by IMU. However, since the tracking with IMU is not possible even in short periods of time, probably the use of an external accurate position sensor is a more reliable approach.

5 Conclusion

In this paper, it has been presented an algorithm to process the samples from an IMU and a further proceeding to compare units performance. The calibration implementation showed to be reliable and can be realized without any external and expensive equipment. The results also confirmed that the Kalman filter ensures a reliable estimation. Two paths have been proposed to evaluate IMUs’ performance, having been concluded that different manufacturing quality units can achieve an equivalent accuracy in terms of orientation estimation, but they are incapable to be used as position tracking sensors. Then, as further improvement, it is suggested the integration of an accurate position sensor for that purpose.