Next Article in Journal
Automated Driving with Cooperative Perception Based on CVFH and Millimeter-Wave V2I Communications for Safe and Efficient Passing through Intersections
Next Article in Special Issue
Advanced Driver Assistance Systems (ADAS) Based on Machine Learning Techniques for the Detection and Transcription of Variable Message Signs on Roads
Previous Article in Journal
Document-Image Related Visual Sensors and Machine Learning Techniques
Previous Article in Special Issue
A Bidirectional Versatile Buck–Boost Converter Driver for Electric Vehicle Applications
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Communication

A Redundant Configuration of Four Low-Cost GNSS-RTK Receivers for Reliable Estimation of Vehicular Position and Posture

by
Jesús Morales
*,
Jorge L. Martínez
and
Alfonso J. García-Cerezo
Robotics and Mechatronic Lab, Andalucía Tech, Universidad de Málaga, 29071 Málaga, Spain
*
Author to whom correspondence should be addressed.
Sensors 2021, 21(17), 5853; https://doi.org/10.3390/s21175853
Submission received: 28 July 2021 / Revised: 20 August 2021 / Accepted: 25 August 2021 / Published: 30 August 2021
(This article belongs to the Special Issue Advances in Intelligent Vehicle Control)

Abstract

:
This paper proposes a low-cost sensor system composed of four GNSS-RTK receivers to obtain accurate position and posture estimations for a vehicle in real-time. The four antennas of the receivers are placed so that every three-antennas combination is optimal to get the most precise 3D coordinates with respect to a global reference system. The redundancy provided by the fourth receiver allows to improve estimations even more and to maintain accuracy when one of the receivers fails. A mini computer with the Robotic Operating System is responsible for merging all the available measurements reliably. Successful experiments have been carried out with a ground rover on irregular terrain. Angular estimates similar to those of a high-performance IMU have been achieved in dynamic tests.

1. Introduction

Acquiring accurate and reliable three-dimensional (3D) coordinates for a vehicle is of great interest in monitoring its operation for advanced driver assistance systems and for autonomous navigation of mobile robots. Vehicle coordinates include three distances for position and three angles for posture with respect to a global reference system on Earth surface, that usually employs North-East-Down (NED) local axes [1].
A common possibility is the use of an Inertial Measurement Unit (IMU), which contain different sensors such as accelerometers, gyroscopes and magnetometers [2]. For proper operation, these units require calibration once installed on the vehicle and to take into account local magnetic field variations. Knowing the initial position of the vehicle, global 3D coordinates can be obtained with an IMU and odometry, but the estimation of the spatial trajectory tends to deteriorate since the measurements include small deviations that accumulate over time [3].
To avoid the growth of position uncertainty, a Global Navigation Satellite System (GNSS) receiver that make use of various global satellite constellations (North American GPS, Russian GLONASS, European Galileo and Chinese BeiDou) at once can be employed [4]. However, absolute GNSS measurements over the Earth’s surface are subject to various types of errors that degrade their accuracy to the order of meters.
GNSS errors can be significantly reduced by incorporating differential corrections provided by a Satellite Based Augmentation Systems (SBAS) or a Continuously Operating Reference Station (CORS) [5]. In this respect, one of the most effective techniques is Real Time Kinematics (RTK) that performs carrier-phase signal synchronization [6] by using the RTCM (Radio Technical Commission for Maritime Services) communication protocol. Thus, GNSS receivers can operate in two different modes: RTK-fixed and RTK-float to indicate when they achieve or not centimeter accuracy, respectively.
Besides, multiple GNSS receivers can be installed onboard to enhance vehicle positioning [5,7]. In addition, a GNSS compass with two antennas can be employed to obtain heading [8,9]. Moreover, by differencing over time the GNSS measurements taken in motion, speed estimations [10] as well as pitch and heading [11] can be deduced.
In field robotics, the combination of GPS and IMU sensors has been a popular option to estimate 3D global coordinates accurately [12]. A different strategy to achieve this objective was to mount the antennas of three high-cost GPS-RTK receivers on the roof of the vehicle [13].
With modern GNSS receivers, the GNSS-IMU sensor combination [14] and the synchronization of three low-cost GNSS-RTK devices [6,15] or three antennas in a single receiver [16] have also been employed in automobiles. Moreover, by tightly coupling three GNSS-RTK receivers and an IMU, accuracy can be improved even more [1,17,18].
This paper proposes a reliable sensor system that provides the position and posture of a vehicle by combining the measurements of four identical GNSS-RTK low-cost receivers. In this way, the main contributions are the following:
  • The best geometrical configuration for three and four antennas to minimize position and posture uncertainty of a vehicle is deduced.
  • A redundant setup with four antennas is analyzed, so when the precision of one receiver degrades, reliable 3D coordinates can be still calculated in real-time.
  • A decentralized node architecture using the Robot Operating System (ROS) that integrates all the available measurements from the receivers is presented.
Regarding the first point, although several antenna configurations have been deployed experimentally on cars, no previous work has performed a theoretical analysis to infer the best layout. This has not prevented two recent papers [6,16] from employing near-optimal configurations for their tests.
With respect to the second contribution, antenna redundancy was previously intended only to improve positioning precision [5,7], but in this paper it also serves to enhance attitude estimations for the vehicle and to tolerate faults on the GNSS receivers.
Regarding the third point, following a low-cost philosophy, it is employed an open-source software of common use in robotics with some already developed nodes in a mini computer instead of programming on specialized boards [6,15,16].
The rest of the paper is organized as follows. Antenna arrangements with three and four GNSS-RTK receivers are discussed in the next Section. Sensor hardware, ROS programming and the optimal calculation of 3D coordinates are described in Section 3. Then, experiments on irregular terrain with the robotic platform Argo XTR are presented in Section 4, including comparisons with measurements from a high-end IMU. Finally, conclusions, acknowledgements, and references complete the paper.

2. Spatial Configurations for the Antennas of the GNSS-RTK Receivers

Let v i be the actual position of an antenna with respect to a global NED coordinate system:
v i ( t ) = x i ( t ) y i ( t ) z i ( t ) = v ¯ i ( t ) + Δ v i ( t ) = x ¯ i ( t ) y ¯ i ( t ) z ¯ i ( t ) + Δ x i ( t ) Δ y i ( t ) Δ z i ( t ) ,
where v ¯ i ( t ) is the measurement produced by the receiver i = 1 , 2 , 3 , 4 at instant t and Δ v i ( t ) is its associated error. The  x , y , z coordinates correspond to north, east, and down displacements, respectively. The covariance matrix for Δ v i is given by:   
C i = E [ Δ v i ( t ) Δ v i T ( t ) ] = E Δ x i ( t ) Δ y i ( t ) Δ z i ( t ) Δ x i ( t ) , Δ y i ( t ) , Δ z i ( t ) = σ x i 2 σ x i y i σ x i z i σ x i y i σ y i 2 σ y i z i σ x i z i σ y i z i σ z i 2 ,
where σ x i 2 = E [ Δ x i 2 ( t ) ] , σ y i 2 = E [ Δ y i 2 ( t ) ] and σ z i 2 = E [ Δ z i 2 ( t ) ] are the variances, whereas σ x i y i = E [ Δ x i ( t ) Δ y i ( t ) ] , σ x i z i = E [ Δ x i ( t ) Δ z i ( t ) ] and σ y i z i = E [ Δ y i ( t ) Δ z i ( t ) ] are the covariances.
For this analysis, it is considered that:
  • The mean errors of the receivers along time are null, i.e.,  E [ Δ v i ( t ) ] = 0 i .
  • The errors of different receivers are independent, i.e.,  E [ Δ v i ( t ) Δ v j T ( t ) ] = 0 for i j .
  • All the receivers share the same covariance matrix, i.e.,  C = C 1 = C 2 = C 3 = C 4 .

2.1. Three Receivers Optimal Configuration

To obtain the optimal configuration for the triangle formed by three GNSS-RTK antennas, its associated position and posture uncertainty should be minimized. In this case, it is also assumed that:
  • The distances d a and d b of the second and third antenna with respect to the first antenna, respectively, are constant values determined without uncertainty.
  • The angle θ between the directions given by d a and d b is also known certainly on the plane that contains the three antennas.
The centroid of the triangle formed by the antennas:
v 0 ( t ) = v 1 ( t ) + v 2 ( t ) + v 3 ( t ) 3 ,
can be estimated from the measurements of the receivers as:
v ¯ 0 ( t ) = v ¯ 1 ( t ) + v ¯ 2 ( t ) + v ¯ 3 ( t ) 3 Δ v 0 ( t ) = Δ v 1 ( t ) + Δ v 2 ( t ) + Δ v 3 ( t ) 3 .
The covariance matrix for Δ v 0 is calculated as:   
C 0 = E Δ v 0 ( t ) Δ v 0 T ( t ) = E Δ v 1 ( t ) Δ v 1 T ( t ) + Δ v 2 ( t ) Δ v 2 T ( t ) + Δ v 3 ( t ) Δ v 3 T ( t ) 9 = C 3 ,
where the position uncertainty of the geometric center of the triangle is reduced by three with respect to each vertex.
Regarding the posture in space of the triangle, the direction cosines of the lines between two antennas are given by the unitary vectors:  
v a ( t ) = v 2 ( t ) v 1 ( t ) d a = x a ( t ) y a ( t ) z a ( t )
v ¯ a ( t ) = v ¯ 2 ( t ) v ¯ 1 ( t ) d a , Δ v a ( t ) = Δ v 2 ( t ) Δ v 1 ( t ) d a ,
v b ( t ) = v 3 ( t ) v 1 ( t ) d b = x b ( t ) y b ( t ) z b ( t )
v ¯ b ( t ) = v ¯ 3 ( t ) v ¯ 1 ( t ) d b , Δ v b ( t ) = Δ v 3 ( t ) Δ v 1 ( t ) d b ,
where the corresponding covariance matrices are:
C a = E Δ v a ( t ) Δ v a T ( t ) = E Δ v 2 ( t ) Δ v 2 T ( t ) d a 2 + E Δ v 1 ( t ) Δ v 1 T ( t ) d a 2 = 2 C d a 2 ,
C b = E Δ v b ( t ) Δ v b T ( t ) = E Δ v 3 ( t ) Δ v 3 T ( t ) d b 2 + E Δ v 1 ( t ) Δ v 1 T ( t ) d b 2 = 2 C d b 2 ,
C a b = E Δ v a ( t ) Δ v b T ( t ) = C b a = E Δ v b ( t ) Δ v a T ( t ) = E Δ v 1 ( t ) Δ v 1 T ( t ) d a d b = C d a d b .
Thus, the spatial uncertainty of the direction cosines can be reduced by separating the antennas as much as possible. But  d a and d b are inherently limited by the available space on the roof of the vehicle. Furthermore, to balance posture uncertainty in both directions, these distances should be selected equal: d = d a = d b , so that C a = C b = 2 C / d 2 and C a b = C b a = C / d 2 .
The direction cosine of the normal vector v c to the plane defined by the three antennas is given by the unitary vector from the cross product of v a and v b :
v c ( t ) = v a ( t ) × v b ( t ) sin ( θ ) = 1 sin ( θ ) y a ( t ) z b ( t ) y b ( t ) z a ( t ) x b ( t ) z a ( t ) x a ( t ) z b ( t ) x a ( t ) y b ( t ) x b ( t ) y a ( t )
v ¯ c ( t ) = 1 sin ( θ ) y ¯ a ( t ) z ¯ b ( t ) y ¯ b ( t ) z ¯ a ( t ) x ¯ b ( t ) z ¯ a ( t ) x ¯ a ( t ) z ¯ b ( t ) x ¯ a ( t ) y ¯ b ( t ) x ¯ b ( t ) y ¯ a ( t ) ,
as long as the three antennas are not aligned to avoid sin ( θ ) = 0 , where v c will be indeterminate.
By using Taylor series expansion [19], v c can be approximated by:
v c ( t ) v ¯ c ( t ) + J ( t ) sin ( θ ) Δ v a ( t ) Δ v b ( t ) Δ v c ( t ) J ( t ) sin ( θ ) Δ v a ( t ) Δ v b ( t ) ,
where J is the time-dependent Jacobian matrix:
J ( t ) = 0 z ¯ b ( t ) y ¯ b ( t ) 0 z ¯ a ( t ) y ¯ a ( t ) z ¯ b ( t ) 0 x ¯ b ( t ) z ¯ a ( t ) 0 x ¯ a ( t ) y ¯ b ( t ) x ¯ b ( t ) 0 y ¯ a ( t ) x ¯ a ( t ) 0 .
The error Δ v c can be minimized regardless of vehicle posture by choosing θ = ± 90 . In this case, the covariance matrix for Δ v c can be approximated by:
C c ( t ) = E [ Δ v c ( t ) Δ v c T ( t ) ] J ( t ) C a C a b C b a C b J T ( t ) = J ( t ) d 2 2 C C C 2 C J T ( t ) .
Finally, the rotation matrix is obtained from the direction cosines as R = v ¯ a , v ¯ b , v ¯ c . Roll, pitch and yaw angles can be deduced from R and represent rotations with respect to v a , v b and v c axis, respectively.
To summarize, the best configuration to minimize position and posture uncertainty with three GNSS-RTK antennas is to form a right-angled triangle with two identical sides of the maximum possible length d (see Figure 1).

2.2. Four Receivers Optimal Layout

The optimum for four receivers would consist of placing the fourth antenna orthogonal to the plane defined by the remaining three at a distance d of the first antenna, where its centroid:
v 0 ( t ) = v 1 ( t ) + v 2 ( t ) + v 3 ( t ) + v 4 ( t ) 4 ,
does not coincide with the geometric center of the underlying cube (see Figure 2).
Assuming perfect placement of the fourth receiver with respect to the triangle:
v c ( t ) = v 4 ( t ) v 1 ( t ) d ,
which can be calculated directly from measurements as:
v ¯ c ( t ) = 1 d x ¯ 4 ( t ) x ¯ 1 ( t ) y ¯ 4 ( t ) y ¯ 1 ( t ) z ¯ 4 ( t ) z ¯ 1 ( t ) Δ v c = Δ v 4 ( t ) Δ v 1 ( t ) d ,
and can be merged with the estimation (14) to decrease posture uncertainty even more. Furthermore, this reduction can also be applied to v ¯ a (7) and v ¯ b (9) with their corresponding normal vectors formed by their respective ortogonal planes: v ¯ a ( t ) = v ¯ b ( t ) × v ¯ c ( t ) and v ¯ b ( t ) = v ¯ c ( t ) × v ¯ a ( t ) , respectively.

2.3. Four Receivers Redundant Configuration

In this paper, an additional fourth receiver is added to the optimal three-receivers configuration to form a square of side d on a planar surface (see Figure 3). This is a redundant arrangement that is easier to mount on the roof of an automobile (see Figure 4) than the optimal one of Figure 2. The local coordinate system has its origin in v 0 with axes v a , v b and v c as defined by (7), (9) and (13), respectively.
In Figure 4, the longitudinal and transverse axes of the car coincide with v a and v b , respectively. The vertical axis v c is not displayed but it would be pointing downwards. This figure also shows the position of a radio antenna, denoted by the letter R, to receive RTK corrections from a CORS.
The proposed redundancy is useful in two different ways. Firstly, position and posture uncertainty can be reduced further than with three receivers. Secondly, if the precision of one of the receivers deteriorates, the rest of receivers can still provide a reliable position and posture estimation for the vehicle.
Regarding the first advantage, when all the measurements are available, its centroid v 0 (18) can be estimated as:  
v ¯ 0 ( t ) = v ¯ 1 ( t ) + v ¯ 2 ( t ) + v ¯ 3 ( t ) + v ¯ 4 ( t ) 4
Δ v 0 ( t ) = Δ v 1 ( t ) + Δ v 2 ( t ) + Δ v 3 ( t ) + Δ v 4 ( t ) 4 C 0 = C 4 ,
whose covariance matrix is divided by four, instead of by three (5). Furthermore, the direction cosines v a and v b can be estimated by using one side of the square and its opposite:
v ¯ a ( t ) = v ¯ 2 ( t ) v ¯ 1 ( t ) + v ¯ 4 ( t ) v ¯ 3 ( t ) 2 d
Δ v a ( t ) = Δ v 2 ( t ) Δ v 1 ( t ) + Δ v 4 ( t ) Δ v 3 ( t ) 2 d C a = C d 2 ,
v ¯ b ( t ) = v ¯ 3 ( t ) v ¯ 1 ( t ) + v ¯ 4 ( t ) v ¯ 2 ( t ) 2 d
Δ v b ( t ) = Δ v 3 ( t ) Δ v 1 ( t ) + Δ v 4 ( t ) Δ v 2 ( t ) 2 d C b = C d 2 ,
that represents half uncertainty of (10) and (11). This reduction directly benefits to the covariance matrix C c (17) of the direction cosine v c :
Δ v c ( t ) J ( t ) Δ v a ( t ) Δ v b ( t ) C c ( t ) J ( t ) d 2 C C C C J T ( t ) ,
where C a b = C b a = C / d 2 .
The second advantage comes from the fact that with a three-antenna configuration, there is no possibility to obtain the complete set of six coordinates for the vehicle when one of the receivers fails. However, the proposed sensor system can keep working with the remaining three receivers. In this case, to obtain the center of the square, instead of the triangle centroid (4), only two measurements from opposite vertices can be employed:
υ ¯ 0 ( t ) = { (28) υ ¯ 2 ( t ) + υ ¯ 3 ( t ) 2 , when   the   first   or   fourth   receiver   fails , (29) υ ¯ 1 ( t ) + υ 4 ( t ) 2 , when   the   sec ond   or   third   receiver   fails ,
which implies that C 0 = C / 2 , i.e., twice position uncertainty with respect to four available measurements (22).

3. Sensor System

In addition to the four low-cost GNSS receivers and their corresponding antennas, the sensor system includes a mini computer to obtain the 3D position and posture of the vehicle (see Figure 5).
The chosen GNSS-RTK receiver is the SparkFun GPS-RTK2 (https://www.sparkfun.com/products/15136, accessed on 28 July 2021) board, which is based on the compact ZED-F9P module from U-blox. The receiver does not only provide geodetic coordinates (longitude, latitude and height), but also ECEF (Cartesian coordinates with respect to Earth center) and NED coordinates with respect to a nearby CORS to obtain centimeter accuracy with an output rate of 8 Hz .
Each receiver is connected to a multi-band antenna ANN-MB-00 (https://www.sparkfun.com/products/15192, accessed on 28 July 2021) from U-blox. To avoid multi-path problems, the magnetic base of each antenna is mounted on a steel ground plate.
The mini computer is an Intel NUC8i7BEH (https://www.intel.es/content/www/es/es/products/sku/126140/intel-nuc-kit-nuc8i7beh/specifications.html, accessed on 28 July 2021) kit with an Intel Core i7-8559U processor (8M Cache, 4 cores, 2.70 GHz). It has installed the open-source framework ROS [20] on the Linux-based operating system Ubuntu.
The computer communicates with each receiver through different Universal Serial Bus (USB) ports. The Internet connection of the computer is used to get differential correction data via the standard protocol NTRIP (Networked Transport of RTCM via Internet Protocol) through the Andalusian public positioning network [21].

ROS Programming

The developed ROS software consists of a number of independent nodes, each of which communicates with others using topics under a publish/subscribe messaging model (see Figure 6).
The ntrip_ros (https://github.com/ros-agriculture/ntrip_ros, accessed on 28 July 2021) node connects to a nearby CORS to get RTCM streams through internet and to publish them into the topic RTCM. Each receiver i has associated a driver node (https://github.com/KumarRobotics/ublox, accessed on 28 July 2021) named gnss_i that is subscribed to this topic to receive differential corrections via callbacks. These nodes publish NED coordinates on its own topic NED_i along with a time stamp and three accuracy estimates (each one 10   m m ).
Then, the reliable_estimator node receives all the messages from the four NED_i topics and computes the six 3D coordinates with three or four synchronized measurements. Finally, it publishes the current pose into the 3D_POSE topic, making this data available for any navigation node on the ROS system.
All the receivers weight the same to produce vehicular position and attitude in real-time. When the accuracy of one receiver degrades, it is completely discarded from computations.
For calculating the global position of the centroid v ¯ 0 of the square (21), (28) or (29) are employed depending on the number of valid GNSS-RTK measurements. For posture computation, the closed-form method by Horn [22] is applied with a scale factor of 1. Instead of quaternions, an orthonormal rotation matrix R [23] is obtained that minimizes the following cost function:
F ( t ) = i ( v i * v 0 * ) R ( t ) v ¯ i ( t ) v ¯ 0 ( t ) 2 ,
where v i * and v 0 * are the relative positions of the antenna i and the centroid of the square with respect to the local reference system, respectively. This represents a least squares problem that can be solved with three or four valid measurements. Lastly, the roll, pitch and yaw angles with respect to the global NED axes are extracted from the resulting rotation matrix [17].

4. Experiments with the Rover Argo XTR

The rover Argo XTR is a battery-powered unmanned land vehicle that allows extreme mobility with a low center of gravity and amphibious capability (see Figure 7). It features skid-steer traction with eight low-pressure 24-inch tires, a top speed of 16 km h−1 and zero turning radius. The robotic rover can be controlled via a follow-me system with a 2D laser scanner or via remote teleoperation with a joystick and a line-of-sight wireless link.
The proposed sensor has been mounted on the rear deck of the vehicle. The four antennas are tied to the side rails forming a square of d = 1.35 m on the side (see Figure 7). For comparison purposes, a fifth antenna has been installed at the center of the square together with the high-end AHRS400CC-100 MEMS IMU from Crossbow with an output rate of 60 Hz [24].
The Málaga broadcast station located 4.8 k m away is employed to get differential corrections RTCM 3.1 through 4G internet connection and it is considered the global NED reference system in the following experiments.

4.1. Calibration Test

This test was carried out by recording the RTK-fixed measurements of the five GNSS receivers during three hours with the rover stopped on an almost horizontal parking lot. This experiment serves to characterize the covariance matriz C for the positioning errors. To this end, the mean NED coordinates are calculated for each receiver and the difference of each measurement with respect to its mean value is considered as an error. Then, by using (2):
C = 10 3 0.0434 0.0025 0.0061 0.0025 0.0694 0.0083 0.0061 0.0083 0.4255 m 2 ,
where it can be observed almost null covariances and a standard deviation in the z coordinate ( σ z = 21   m m ) much greater than in the x ( σ x = 7   m m ) and in the y ( σ y = 8   m m ) coordinates.
Moreover, the relative location of each antenna v i * can also be accurately estimated with the computed mean values (see Table 1). It can be observed small positioning errors on the square with the fifth antenna centered and 166 m m below the rest of antennas. Table 1 also includes the local position of the centroids of the square v 0 * for (30) when using four or three receivers.

4.2. Reliability Test

This test was performed with the vehicle stopped in the countryside as shown in Figure 7. One by one, each GNSS antenna was partially blocked with a metallic cover during one minute approximately to test sensor reliability.
Figure 8 shows the estimation of NED coordinates when using all (21), the first and the fourth (28) or the second and the third (29) receivers. Similarly, Figure 9 displays the estimation of the three angular coordinates with all the combinations of three and four receivers. In both figures, it can be clearly observed significant estimation changes when an antenna was temporarily blocked.
The mean accuracy provided by each receiver is shown in Figure 10 (up), where it can be observed successive antenna covering, in this order: 3, 1, 4 and 2. Apart from checking the RTK-fixed mode, these values can be employed as a fail indicator for each receiver. However, there is a time period between 325 s to 350 s when the indicator for the first receiver does not detect any error but position and posture estimations were inaccurate.
An additional accuracy indicator is the error in calculating the perimeter of the square from measurements with respect to the data of Table 1 ( 5.389   m ). As it is shown in Figure 10 (down), precision degradation can be better detected by using this complementary indicator. Thus, by comparing individually the distances of each vertex with respect to the rest, outlier measurements can be identified adequately when present.
Furthermore, in Figure 8 and Figure 9, it can be observed that the estimations that do not include the failing measurement maintain high accuracy. For example, when the precision of the first receiver degrades in the interval between 290 s to 350 s , good position and posture estimations are provided by the second and third receivers, and by the second, third and fourth receivers, respectively. Therefore, overall accuracy for the sensor system can be maintained by properly detecting a single failure and excluding it from computations.

4.3. Dynamic Test

Several experiments were performed by teleoperating the robotic rover on rough countryside. Figure 11 presents an aerial view of one of them using geodetic coordinates for the grid. The beginning and the end of the path, that almost coincide, are marked with a green square and a red circle, respectively. In total, the vehicle travelled 644 m at a mean speed of 4.6   k m h −1.
Figure 12 shows the three NED coordinates obtained by the proposed sensor system and by the fifth receiver at the center of the square formed by the antennas. There are no appreciable differences between both estimations, with the exception of the step of 0.166   m in the down coordinate (see Table 1). Altogether, the rover went up and, then, under 12 m .
Figure 13 displays the rover posture obtained by the GNSS setup and by the onboard IMU. It can be observed high peaks in the pitch (above 15°) and the roll (above 25°) angles, as well as several complete turns in the yaw angle during the test. Both estimations are very similar, which confirms the good performance of the proposed sensor system.

5. Conclusions

A low-cost sensor system composed of four GNSS-RTK receivers connected to a mini computer has been presented in the paper. The placement of three antennas on a vehicle have been analyzed to reduce the uncertainty associated to position and posture estimations with respect to a global reference system. The redundant fourth receiver allows to improve estimations even more and to maintain accuracy when the precision of one of the receivers deteriorates.
Static calibration and reliability tests have been performed with the sensor system mounted on the ground rover Argo XTR. Dynamic experiments on countryside show that this new sensor, in addition to produce reliable positioning, can effectively substitute a high performance IMU to obtain accurate vehicular roll, pitch and yaw angles in real-time.
Future work includes characterizing the achieved pose precision with the robotic rover as well as developing ROS nodes for integrating the proposed sensor system with an IMU for GNSS-denied environments.

Author Contributions

J.M. and J.L.M. conceived the research. J.M. developed the software. J.M. and J.L.M., perform the experiments and analyzed the results. J.L.M. and J.M. wrote the paper and elaborated the figures. J.M. and A.J.G.-C. were in charge of project administration. All authors have read and agreed to the published version of the manuscript.

Funding

This work was partially supported by the Andalusian project UMA18-FEDERJA-090 and the Spanish project RTI2018-093421-B-I00.

Conflicts of Interest

The authors declare no conflict of interest.

Abbreviations

The following acronyms are used in the manuscript:
3DThree-Dimensional
CORSContinuously Operating Reference Station
ECEFEarth-Centered, Earth-Fixed
GPSGlobal Positioning System
GNSSGlobal Navigation Satellite System
IMUInertial Measurement Unit
MEMSMicro Electro Mechanical Systems
NTRIPNetworked Transport of RTCM via Internet Protocol
ROSRobot Operating System
RTCMRadio Technical Commission for Maritime Services
SBASSatellite Based Augmentation Systems
USBUniversal Serial Bus

References

  1. Henkel, P. Calibration of magnetometers with GNSS receivers and magnetometer-aided GNSS ambiguity fixing. Sensors 2017, 17, 1324. [Google Scholar] [CrossRef] [Green Version]
  2. Ahmad, N.; Ariffin, R.; Ghazilla, R.; Khairi, N.M.; Kasi, V. Reviews on various Inertial Measurement Unit (IMU) sensor applications. Int. J. Signal Proc. Syst. 2013, 1, 256–262. [Google Scholar] [CrossRef] [Green Version]
  3. Borenstein, J.; Everett, H.R.; Feng, L.; Wehe, D. Mobile robot positioning: Sensors and techniques. J. Robot. Syst. 1997, 14, 231–249. [Google Scholar] [CrossRef]
  4. Hein, G.W. Status, perspectives and trends of satellite navigation. Satell. Navig. 2020, 1, 1–12. [Google Scholar] [CrossRef]
  5. Ciecko, A.; Bakula, M.; Grunwald, G.; Cwiklak, J. Examination of multi-receiver GPS/EGNOS positioning with Kalman filtering and validation based on CORS stations. Sensors 2020, 20, 2732. [Google Scholar] [CrossRef] [PubMed]
  6. Olivart-Llop, J.M.; Moreno-Salinas, D.; Sánchez, J. Full real-time positioning and attitude system based on GNSS-RTK technology. Sustainability 2020, 12, 9796. [Google Scholar] [CrossRef]
  7. Fastellini, G.; Radicioni, F.; Schiavoni, A.; Stoppini, A. Comparison of kinematic parameters of a moving vehicle by GNSS measurements and inertial/GPS navigation system. In Proceedings of the 5th International Symposium on Mobile Mapping Technology (MMT), Padua, Italy, 29–31 May 2007; pp. 28–31. [Google Scholar]
  8. Consoli, A.; Ayadi, J.; Bianchi, G.; Pluchino, S.; Piazza, F.; Baddour, R.; Pares, M.E.; Navarro, J.; Colomina, I.; Gameiro, A.; et al. A multi-antenna approach for UAV’s attitude determination. In Proceedings of the 2nd International Workshop on IEEE Metrology for Aerospace (MetroAeroSpace), Benevento, Italy, 3–5 June 2015; pp. 401–405. [Google Scholar] [CrossRef]
  9. Liu, S.; Zhang, L.; Li, J. A dual frequency carrier phase error difference checking algorithm for the GNSS compass. Sensors 2016, 16, 1988. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  10. Ding, W.; Wang, J. Precise velocity estimation with a stand-alone GPS receiver. J. Nav. 2011, 64, 311–325. [Google Scholar] [CrossRef] [Green Version]
  11. Sun, R.; Cheng, Q.; Wang, J. Precise vehicle dynamic heading and pitch angle estimation using time-differenced measurements from a single GNSS antenna. GPS Solut. 2020, 24, 1–9. [Google Scholar] [CrossRef]
  12. Sukkarieh, S.; Nebot, E.M.; Durrant-Whyte, H.F. A high integrity IMU/GPS navigation loop for autonomous land vehicle applications. IEEE Trans. Robot. Autom. 1999, 15, 572–578. [Google Scholar] [CrossRef] [Green Version]
  13. Blanco, J.L.; Moreno, F.A.; González, J. A collection of outdoor robotic datasets with centimeter-accuracy ground truth. Auton. Robot. 2009, 27, 327–351. [Google Scholar] [CrossRef]
  14. Maddern, W.; Pascoe, G.; Gadd, M.; Barnes, D.; Yeomans, B.; Newman, P. Real-time kinematic ground truth for the Oxford robotcar dataset. arXiv 2020, arXiv:2002.10152. [Google Scholar]
  15. Lourakis, M.; Pateraki, M.; Karolos, I.A.; Pikridas, C.; Patias, P. Pose estimation of a moving camera with low-cost, multi-GNSS devices. In Proceedings of the International Archives of the Photogrammetry, Remote Sensing and Spatial Information Sciences, XXIV ISPRS Congress, Nice, France, 31 August–2 September 2020; pp. 55–62. [Google Scholar] [CrossRef]
  16. Zhg, R. Entanglement difference of GNSS carrier phase for vehicle attitude determination. Int. J. Transp. Sci. Tech. 2021, 10, 69–82. [Google Scholar] [CrossRef]
  17. Cai, X.; Hsu, H.; Chai, H.; Ding, L.; Wang, Y. Multi-antenna GNSS and INS integrated position and attitude determination without base station for land vehicles. J. Nav. 2019, 72, 342–358. [Google Scholar] [CrossRef]
  18. Henkel, P.; Sperl, A.; Mittmann, U.; Fritzel, T.; Strauss, R.; Steiner, H. Precise 6D RTK positioning system for UAV-based near-field antenna measurements. In Proceedings of the 14th European Conference on Antennas and Propagation (EuCAP), Copenhagen, Denmark, 15–20 March 2020; pp. 1–5. [Google Scholar] [CrossRef]
  19. Smith, R.C.; Cheeseman, P. On the representation and estimation of spatial uncertainty. Int. J. Robot. Res. 1986, 5, 56–67. [Google Scholar] [CrossRef]
  20. Quigley, M.; Gerkey, B.; Conley, K.; Faust, J.; Foote, T.; Leibs, J.; Berger, E.; Wheeler, R.; Ng, A. ROS: An open-source robot operating system. In Proceedings of the IEEE International Conference on Robotics and Automation: Workshop on Open Source Software (ICRA), Kobe, Japan, 12–17 May 2009. [Google Scholar]
  21. Berrocoso, M.; Páez, R.; Jijena, B.; Caturla, C. The RAP net: A geodetic positioning network for Andalusia (south Spain). In Proceedings of the EUREF Symposium, Riga, Latvia, 14–16 June 2006; pp. 364–368. [Google Scholar]
  22. Horn, B.K.P. Closed-form solution of absolute orientation using unit quaternions. J. Opt. Soc. Am. 1987, 4, 629–642. [Google Scholar] [CrossRef]
  23. Bandari, E.; Goldstein, N.; Nesnas, I.; Bajracharya, M. Realtime Absolute Orientation with Outlier Rejection for Visual Odometry and Mesh Merging; Technical Report 20040084602; National Aeronautics and Space Administration (NASA): Washington, DC, USA, 2004.
  24. Niu, X.; Goodall, C.; Nassar, S.; El-Sheimy, N. An efficient method for evaluating the performance of MEMS IMUs. In Proceedings of the IEEE/ION Position, Location, And Navigation Symposium, San Diego, CA, USA, 25–27 April 2006; pp. 766–771. [Google Scholar]
Figure 1. Optimal antenna configuration with three receivers.
Figure 1. Optimal antenna configuration with three receivers.
Sensors 21 05853 g001
Figure 2. Optimal antenna configuration with four receivers.
Figure 2. Optimal antenna configuration with four receivers.
Sensors 21 05853 g002
Figure 3. Redundant antenna configuration with four receivers.
Figure 3. Redundant antenna configuration with four receivers.
Sensors 21 05853 g003
Figure 4. Placement of the antennas on the roof of a car.
Figure 4. Placement of the antennas on the roof of a car.
Sensors 21 05853 g004
Figure 5. Hardware components of the sensor system: a GNSS-RTK board (a), an antenna (b), a ground plate (c) and the mini computer (d).
Figure 5. Hardware components of the sensor system: a GNSS-RTK board (a), an antenna (b), a ground plate (c) and the mini computer (d).
Sensors 21 05853 g005
Figure 6. ROS computation graph with nodes (ellipses) and topics.
Figure 6. ROS computation graph with nodes (ellipses) and topics.
Sensors 21 05853 g006
Figure 7. The rover Argo XTR with the sensor system mounted on the rear deck. GNSS antennas are numbered from 1 to 5.
Figure 7. The rover Argo XTR with the sensor system mounted on the rear deck. GNSS antennas are numbered from 1 to 5.
Sensors 21 05853 g007
Figure 8. Estimation of position coordinates during the reliability test.
Figure 8. Estimation of position coordinates during the reliability test.
Sensors 21 05853 g008
Figure 9. Estimation of posture coordinates during the reliability test.
Figure 9. Estimation of posture coordinates during the reliability test.
Sensors 21 05853 g009
Figure 10. Accuracy estimation during the reliability test.
Figure 10. Accuracy estimation during the reliability test.
Sensors 21 05853 g010
Figure 11. Aerial view of the path followed by the rover on the countryside.
Figure 11. Aerial view of the path followed by the rover on the countryside.
Sensors 21 05853 g011
Figure 12. Comparison between the position coordinates obtained by the fifth receiver and the proposed sensor.
Figure 12. Comparison between the position coordinates obtained by the fifth receiver and the proposed sensor.
Sensors 21 05853 g012
Figure 13. Comparison between the posture coordinates obtained by the IMU and the proposed sensor.
Figure 13. Comparison between the posture coordinates obtained by the IMU and the proposed sensor.
Sensors 21 05853 g013
Table 1. Relative coordinates of the antennas and of the square centroid.
Table 1. Relative coordinates of the antennas and of the square centroid.
a (m)b (m)c (m)
v 1 * −0.672−0.675−0.004
v 2 * 0.673−0.676−0.004
v 3 * −0.6720.672−0.004
v 4 * 0.6710.6780.011
v 5 * −0.0040.0050.166
v 0 * (21)000
v 0 * (28)0.001−0.002−0.004
v 0 * (29)00.0020.004
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Morales, J.; Martínez, J.L.; García-Cerezo, A.J. A Redundant Configuration of Four Low-Cost GNSS-RTK Receivers for Reliable Estimation of Vehicular Position and Posture. Sensors 2021, 21, 5853. https://doi.org/10.3390/s21175853

AMA Style

Morales J, Martínez JL, García-Cerezo AJ. A Redundant Configuration of Four Low-Cost GNSS-RTK Receivers for Reliable Estimation of Vehicular Position and Posture. Sensors. 2021; 21(17):5853. https://doi.org/10.3390/s21175853

Chicago/Turabian Style

Morales, Jesús, Jorge L. Martínez, and Alfonso J. García-Cerezo. 2021. "A Redundant Configuration of Four Low-Cost GNSS-RTK Receivers for Reliable Estimation of Vehicular Position and Posture" Sensors 21, no. 17: 5853. https://doi.org/10.3390/s21175853

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop