Next Article in Journal
A Remote Raman System and Its Applications for Planetary Material Studies
Next Article in Special Issue
WPAN and IoT Enabled Automation to Authenticate Ignition of Vehicle in Perspective of Smart Cities
Previous Article in Journal
From Fully Physical to Virtual Sensing for Water Quality Assessment: A Comprehensive Review of the Relevant State-of-the-Art
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Enhanced PDR-BLE Compensation Mechanism Based on HMM and AWCLA for Improving Indoor Localization

1
Department of Electronics Engineering, Jeju National University, Jejusi 63243, Korea
2
Department of Computer Engineering, Jeju National University, Jejusi 63243, Korea
*
Author to whom correspondence should be addressed.
Sensors 2021, 21(21), 6972; https://doi.org/10.3390/s21216972
Submission received: 3 September 2021 / Revised: 1 October 2021 / Accepted: 5 October 2021 / Published: 21 October 2021

Abstract

:
This paper presents an enhanced PDR-BLE compensation mechanism for improving indoor localization, which is considerably resilient against variant uncertainties. The proposed method of ePDR-BLE compensation mechanism (EPBCM) takes advantage of the non-requirement of linearization of the system around its current state in an unscented Kalman filter (UKF) and Kalman filter (KF) in smoothing of received signal strength indicator (RSSI) values. In this paper, a fusion of conflicting information and the activity detection approach of an object in an indoor environment contemplates varying magnitude of accelerometer values based on the hidden Markov model (HMM). On the estimated orientation, the proposed approach remunerates the inadvertent body acceleration and magnetic distortion sensor data. Moreover, EPBCM can precisely calculate the velocity and position by reducing the position drift, which gives rise to a fault in zero-velocity and heading error. The developed EPBCM localization algorithm using Bluetooth low energy beacons (BLE) was applied and analyzed in an indoor environment. The experiments conducted in an indoor scenario shows the results of various activities performed by the object and achieves better orientation estimation, zero velocity measurements, and high position accuracy than other methods in the literature.

1. Introduction

Indoor location-based services (LBS) have always been of great importance because people live and work in indoor environments most of their lives. Massive wireless networks are built according to the IEEE 802.11 wireless Ethernet standard [1]. LBS are the backbone of indoor mobile positioning techniques [2]. Global navigation satellite systems (GNSS) and global positioning systems (GPS) have helped us provide accurate location services for outdoor environments. Still, these services are impeded by signal absorption and hamper in specific environments (e.g., dense forests, mountainous regions, underground facilities, and high-rise buildings) [3]. GNSS and GPS take the user′s three-dimensional information (i.e., longitude, altitude, and latitude) [4]. The accuracy of these services depends upon the line of sight, and if the precision is good, object detection is possible within meters. Therefore, to come up with an overall location service, a number of technologies have emerged for indoor positioning; for instance, radio frequency identification (RFI) [5], pseudo-satellites [6], indoor ultrasonic positioning (UIP) [7], indoor positioning approach using iBeacon [8], ultra-wideband (UWB) technology allows micro-positioning of objects along with obstacles [9], and indoor positioning based on ZigBee [10].
A large variety of reconfigured wireless devices (RWD) are already in use, namely Bluetooth low energy (BLE) beacons, smartphones, Wi-Fi, ultra-wideband (UWB) beacons, and digital cameras for indoor positioning [11,12]. For purpose-built installations, these RWDs are placed strategically throughout a defined space. IPS uses different localization mechanisms, including the position estimation of tagging devices from nearby anchor nodes, such as BLE, UWB, and Wi-Fi access points (AP) with known fixed positions. Weighted centroid localization (WCL) [13], distance vector hop (DV-Hop) localization [14], trilateration-based localization, context-recognition aided-based PDR localization [15], and fingerprinting-based localization techniques are also used [16]. In recent years, researchers have focused on related technologies and methods that provide high precision positioning services.
Pedestrian dead reckoning (PDR) is an independent approach, and its primary principle is to calculate the step length, determine walking direction, and step size by using inertial sensors (IS) (i.e., accelerometer, gyroscope, and geomagnetic meter) to calculate the moving target information and positions [17]. Bluetooth low energy beacon is pulled in for indoor localization technology because of low energy communication via the Bluetooth beacons and broadcasting low-energy Bluetooth signals in a given range. BLE beacons send out an ID number via BLE channels triggering a specific action relevant to the location approximately ten times every second [18]. The distance between BLE beacons and smartphones was computed based on the received signal strength indicator (RSSI) values. To estimate the position, we used the centroid localization algorithm (CLA) and weighted centroid localization algorithm (WCLA) proposed by [17,18,19], which uses the BLE beacon coordinations to estimate the position of the smartphone. The position accuracy using CLA is very low in WCLA when using weight to improve position accuracy. In AWCLA, location accuracy is increased, but still, the error accuracy is high. Different filters were used to get the precise output, e.g., complementary filter, low-pass filter, Butterworth filter, Kalman filter, extended Kalman filter, unscented Kalman filter, alpha–beta filter, Gaussian filter, etc. These filters are used in the literature as data fusion filters, responsible for removing noise from sensor values and producing an estimate of the system′s state by taking the average of the new measurement and the system′s predicted state using a weighted average. Furthermore, different machine learning-based models were also developed to estimate the position in an indoor environment. Still, due to the massive amount of sensing data, these systems cannot provide a real-time position estimation because of high computational requirements. Due to advanced and sophisticated machine learning techniques, it is therefore required to estimate the real-time position of an object in an indoor environment by using a lightweight, intelligent solution. Machine learning techniques have been utilized in many fields, such as healthcare, finance, irony detection, citation classification, effective waste management, energy consumption forecasting, boreholes data analysis, groundwater resource planning, and education, to name of a few [20,21,22,23,24,25].
In this study, EPBCM was developed to track the position of an object in an indoor environment. Quaternions and their conversion to Euler angles are explained. Smartphone-based inertial measurement unit (IMU) sensors were used for the data collection. A complementary filter was used to integrate the information of pitch, roll, and angular velocity to obtain orientation tracking. The state vector used for the estimation of orientation in UKF contains the prior gyros bias errors and Euler angle errors. The HMM-based activity detection approach was developed to recognize the various activities (running, walking, writing on a whiteboard, working on the computer, walking upstairs) performed by the smartphone user. The state transitions probability matrix and observation probability matrix were calculated based on the changing magnitudes of the accelerometer values. The compensation mechanism increases the position accuracy by reducing the drift error. KF was used for smoothing RSSI measurements obtained from the BLE beacon. The average weighted centroid localization algorithm (AWCLA) was used for the proximity calculation between the smartphone and fixed BLE beacon position. Various performance analyses were used to evaluate the significance of the proposed EPBCM based on HMM and AWCLA, such as clustering of raw data to know about the activities performed, comparison of position accuracy of PDR, BLE, and EPBCM, indoor localization visualization using IMU sensor data, and orientation estimation based on AHRS and UKF.
The notable contributions of the proposed study is as follows:
  • Developed mechanism based on complementary filter to integrate roll, pitch, and angular velocity information to obtain orientation tracking information.
  • Developed HMM-based activity detection approach to recognize the various performed activities.
  • Smoothing of RSSI measurements by passing through the Kalman filter to remove noise and enhance the accuracy of distance calculation between the beacon and mobile phone user.
  • Weight assignment based on the power of RSSI measurements and use of AWCLA for the proximity calculation between the BLE beacon and smartphone.
  • Furthermore, different evaluation metrics were utilized to evaluate the effectiveness of the proposed EPBCM based on HMM and AWCLA, such as a comparison, in terms of position accuracy, confirmation of activity detection by clustering the sensor data to visualize the performed activities and compare with HMM-based activity detection approach, and comparison of the orientation estimation approach based on AHRS and UKF.
The rest of the paper is divided into the following sections. Section 2 presents the related works; Section 3 presents enhanced PDR-BLE compensation mechanism based on HMM and AWCLA for Improving indoor localization. Section 4 presents Compensation mechanism based on AWCLA. Section 6 discusses experimental design, implementation environment, comparison of proposed system with state-of-the-art-techniques, and performance analysis. Section 7 concludes the paper with possible future directions.

2. Related Work

The internet of things is an evolving field, attracting much attention from the research community [26,27,28,29,30,31,32,33,34,35,36,37,38,39,40,41,42,43]. The systems pertaining to location tracking and intelligent navigation are widely employed to handle specific scenarios related to security, logistic medicine, and mission-critical indoors. Indoor Localization is deemed one of the quintessential areas among all of them because of excessive location-based services [44]. Therefore, indoor positioning is a popular topic that is gaining popularity. It is a network of devices used to locate objects or people where global navigation satellite system (GNSS) and global positioning system (GPS) technologies lack exactness or are completely unsuccessful, particularly parking garages, underground locations, multistory buildings, railway stations, and airports. The dependency of multiple computing concepts on positionings, such as location and context-aware systems and ubiquitous computing, shows how important the indoor positioning systems (IPS) hold [45]. To find the accurate location where the GPS signal is lost, radio-frequency signals have been developed. When compared to the classic Bluetooth, Bluetooth low energy beacons are low in cost, low in energy consumption, and small in size [18]. Distance computation between beacons and smartphones can be done by using BLE beacons. To determine a single point in a two-dimensional space, a minimum of three beacons are required if considering the trilateration scenario [46]. Indirect distance computation involves the measurement of RSSI values.
A microelectromechanical systems (MEMS) are used to offer beacon-free solutions, consisting of a gyrometer, an accelerometer, and magnetometer. Due to the lightweight, smaller size, and lower cost of MEMS, sensors are often employed for the PDR system. Conventionally, the indirect estimation of walking speed and walking direction is conducted by using the PDR approach [47]. PDR can only obtain relative positioning results, has high position accuracy, and cumulative errors. However, PDR is a self-confined approach, but will produce a growing drift as the walking distance increases [48]. To reduce the errors, bias, and bias instability that accumulate through the navigation equation at the output of MEMS sensors can be contained by attaching inertial measurement sensors (IMU) on foot and other body parts to recognize particular activities and by using the zero-velocity update (ZVU) algorithm to predict the position [49,50]. The velocity and the acceleration integral of the foot are practically zero when the stance phase occurs during the motion of the pedestrian [51]. Therefore, an error in the foot orientation increases the position′s error to grow linearly with time. Similarly, the calculation of the non-gravitational acceleration is affected by the attitude errors. If the orientation and attitude errors are not tackled rightly, the combined result induces a worse position estimation. The erroneous step increased position error. Therefore, a low false detection rate, in estimating each step′s start and end is conducive to improve accuracy. In [52], for precise human body part orientation tracking, the author reviewed the filtering techniques and main sensor fusion. The author in [53] deals with the nonlinear attitude prediction system and linearization of the currently estimated points of the model in the PDR system by using the extended Kalman filter (EKF). For attitude estimation, the author in [54] proposed the hidden Markov model (HMM) based EKF. To enhance the results of the roll, pitch, and yaw for orientation tracking, the author developed a double-stage Kalman filter (KF) in [55]. In attitude estimation of PDR, when the nonlinear characteristic is extreme, for instance, environmental magnetic variation, variation in acceleration based on human motion, the attitude dynamics, etc., causes divergence of the EKF and degrades the accuracy. To enhance the performance of PDR by using a sophisticated ZVU algorithm in [56], the author achieved ∼4% distance error by incorporating the two outputs of the maximum bounds at the stance phase by implementing a binary decision-making rule. The study in [57] shows that the author knows the sensor data, based on sensor knowledge, examines the acceleration-magnitude detector, acceleration-moving variance detector, and the angular rate energy detector. The paper shows that all detectors can be derived by using the general likelihood ratio test (LRT) framework. To accurately distinguish stance phases, the author in [57] proposed a clustering algorithm. In [58,59], the authors suggest that HMM chains classify human activities, and [60] show that there are more computational costs for the hierarchically structured approaches. The author in [61] used a smartphone-based IMU sensor for activity recognition to facilitate the people who had chronic neurodegenerative diseases, such as Alzheimer′s.
To identify and track objects automatically, various technologies related to indoor positioning include Wi-Fi, ultra wide band (UWB), radio frequency identification (RFID), and BLE. To achieve better positioning accuracy and to reduce the positioning system cost based on RFID, the authors in [62] presented a hyperbolic positioning algorithm and in [63] convert paths that are non-line of sight (NLOS) to the paths which are line of sight (LOS) by employing a hybrid method based angel of arrival (AOA) and phase difference of arrival (PDOA). Positioning using BLE beacons in an indoor environment, the author suggested a hybrid method, combining dead reckoning and trilateration [64]. In [65], the authors suggested KF, to smooth the RSSI measurements obtained from the installed BLE beacons and developed an android application to locate a user inside a building. There were high computational and processing times in the UWB-PDR-based localization algorithm. Due to the increased numbers of anchors in the localization algorithm, the system cost also increased [66]. In [67], WCL and fingerprint techniques are used for indoor localization based on the least square method. Improvements are being made in the WCL localization algorithm by [68]. However, the estimated error is still significantly high.
To predict and measure the motion of the body based on IMU wearable devices, many machine learning algorithms are used. To reduce the error in an indoor environment, a deep neural network fingerprinting based indoor positioning approach is used [69]. In [70], the author used inertial sensor data to detect step length and step detection by using ANN and RNN. In another paper, the author used the feed-forward NN approach to get the location at the output [71]. Similarly, in [72], based on RSS measurements of Wi-Fi access point nodes, the author suggested a radial basis function to find the location of a user. As mentioned above in Table 1, the critical analysis of indoor localization based on the BLE-beacon, PDR machine learning algorithms, and the combined hybrid approach has many drawbacks in system performance and accuracy. To predict and identify the object or location, these approaches directly use sensor data as an input to the machine learning algorithm. The drifting error and bias in sensor readings affect the accuracy of the position estimation.
To the best of the authors′ knowledge, all of the indoor positioning systems are developed based on single or hybrid localization algorithms that have problems of high position errors and more computational costs, particularly for hybrid localization algorithms. Moreover, all of these only determine the location of an object in an indoor environment. In some cases, sensors mounted on the foot, hand, arm, and chest are considered to track the orientation and detect the activity of an object up to the binary level. Furthermore, all of these existing indoor positioning systems face different issues, such as high localization errors, high computational costs, and high hardware costs, to name of few, as mentioned in Table 1. Therefore, a new solution is required to track the position and detect the activities performed by the object, which aims to minimize latency, maximize position accuracy, and provide better orientation estimation. A compensation mechanism is developed to reduce the effect of the drift caused by the dead reckoning localization algorithm. Proximity calculation between beacons and smartphones are also improved by using AWCLA and passing RSSI measurements through the Kalman filter. This enhanced hybrid localization algorithm is presented in the following sections.

3. Enhanced PDR-BLE Compensation Mechanism Based on HMM and AWCLA for Improving Indoor Localization

3.1. Design of Proposed EPBCM Localization Algorithm

In this section, an EPBCM based on HMM and AWCLA was implemented to decrease drift and error in the position caused by navigation algorithms. The details of the proposed EPBCM are shown in Figure 1. A brief explanation of each step and mathematical formulation used to calculate the orientation, x,y coordinates through various localization techniques, and detection of activities of an object in an indoor environment by considering the HMM are presented in the below sub-sections. Table 2 presents notations and symbols used in mathematical formulation.

3.1.1. Quaternions Calculation

The orientation between the inertial navigational frame { i n f } and the sensor-body frame { s b f } can be represented by adopting quaternions. The scaler part of quaternions consist of s R and v ( x , y , z ) , which is a vector part and are expressed as q ( s , v ) , where v R 3 . The vector part of the quaternions can be represented into two different frames q and q as v i n f = q v s b f q . The vector in the sensor body frame { s b f } refers to v s b f and the inertial navigational frame { i n f } refers to vector v i n f , and ⨂ denotes the multiplication operations between vectors. A quaternion number is represented in the form of real and imaginary elements, where i , j , and k are basis elements and α , β , γ and δ are real numbers α + β i + γ j + δ k . The unit-vector quaternion q i n f s b f encoding rotation from the inertial frame to the body frame of the sensor q i n f s b f = ( α σ 1 σ 2 σ 3 ) T .
The amount of the rotation that should be performed about the vector part specifies by the element α , where as elements σ 1 , σ 2 , and σ 3 , thought of as a vector about which rotation should be performed. q i n f s b f = ( α σ T ) T . If ϕ is the angle of rotation and the vector ε = ( ε x ε y ε z ) T is a unit vector representing the axis of rotation, then the quaternion elements are defined as a unit quaternion q 2 = α 2 + σ 1 2 + σ 2 2 + σ 3 2 = 1 . A simple rotation can transform a vector from one reference frame to another according to Euler′s rotation theorem, and this is done by rotating ϕ about a unit vector ϵ . This unit vector representing the axis of rotation, and the quaternion elements are defined as:
α σ 1 σ 2 σ 3 = cos φ 2 ε x sin φ 2 ε y sin φ 2 ε z sin φ 2
or as a rotation matrix Q ( q ) = I + 2 α S ( σ ) + 2 S 2 ( σ ) , S( σ ) = 0 σ 3 σ 2 σ 3 0 σ 1 σ 2 σ 1 0 , Q ( q ) = ( c o s ϕ 2 , ( ε x ε y ε z ) T × s i n ϕ 2 . The set of quaternions, defined within a four-dimensional vector space over the real numbers R 4 is denoted by Q. Quaternions q i n f s b f can be used to rotate an arbitrary three-element vector from the inertial frame to the body frame using the matrix multiplication operation v s b f = Q i n f s b f ( q i n f s b f ) v i n f . To rotate a vector from the inertial navigational frame to the sensor body frame, the attitude quaternion can be used to construct a 3 × 3 rotation matrix, to perform the rotation in a single matrix multiply operation expressed as:
Q i n f s b f q i b   = α 2 + σ 1 2 + σ 2 2 + σ 3 2 2 σ 1 σ 2 2 α σ 3 2 σ 1 σ 3 + 2 α σ 2 2 σ 1 σ 2 + 2 α σ 3 α 2 σ 1 2 + σ 2 2 σ 3 2 2 σ 2 σ 3 2 α σ 1 2 σ 1 σ 3 2 α σ 2 2 σ 2 σ 3 + 2 α σ 1 α 2 σ 1 2 σ 2 2 + σ 3 2
The rotation can be reversed by simply inverting the attitude quaternion q i n f s b f before performing the rotation. Likewise, the operation can be reversed by negating the vector part of the quaternion vector. Euler angles are intuitive and straightforward for simple analysis and control, but these are limited by a gimbal lock, which prevents Euler angles from measuring orientation when the pitch angle approaches ± 90 .

3.1.2. Quaternions Calculation at North–East Down (NED)

The inertial frame is an unmoving Earth-fixed set of axes reference. In the inertial frame, x-axes point north, y-axes point east, and z-axes point down. This configuration of axes in the inertial frame reference is called north–east Down (NED). The sequence of rotations is used to represent a given orientation, which is the first yaw, then pitch, and finally roll. YAW rotation results in the new coordinate frame as illustrated in the Figure 2a. Yaw represents rotation about the inertial-frame z-axis by an angle ψ . The rotation of yaw around the z-axis produces a new coordinate frame where the z-axis is aligned with the inertial frame, and the yaw angle ψ rotates the x and y axes The orientation of the new coordinate frame after the rotation of yaw is shown in Figure 2b.
Q i n f n e w f 1 ( ψ ) = cos ( ψ ) sin ( ψ ) 0 sin ( ψ ) cos ( ψ ) 0 0 0 1
Similarly, if the rotation around pitch represents ξ and the pitch is not rotating about the inertial frame Y-axis as shown in Figure 2, it is because that change in orientation occurs due to the changing in frames. This can be seen in Equations (4) and (5).
Q newf   1 newf 2 ( ξ ) = cos ( ξ ) 0 sin ( ξ ) 0 1 0 sin ( ξ ) 0 cos ( ξ )
Q i n f newf   1 ( ξ , ψ ) = Q n e w f 1 new   f 2 ( ξ ) Q inf newf ( ψ )
Performing rotation around the newf
2 x-axis, SBF is obtained. The SBF contains yaw, pitch, and roll, and the rotation matrix for moving from the newf2 to SBF is given by:
Q newf   2 s b f ( φ ) = 1 0 0 0 cos ( φ ) sin ( φ ) 0 sin ( φ ) cos ( φ ) .
To complete the rotation matrix for moving from the inertial frame to the body frame—it is shown in Equation (7)
Q i n f s b f = ( φ , ξ , ψ ) = Q n e w f 2 s b f ( φ ) Q n e w f 1 n e w f 2 ( ξ ) Q i n f n e w f 1 ( ψ ) .
To get the accurate angular rates in the proper frames, the x-axis IMU output must be rotated into the newf2 frame, the y-axis IMU output must be rotated into the newf1 frame, and the z-axis IMU output must be turned into the INF. The resulting transformation matrix for converting body-frame angular rates to Euler angular rates is given by
E = ( φ , ξ , ψ ) = 1 sin ( φ ) tan ( ξ ) cos ( φ ) tan ( ξ ) 0 cos ( φ ) sin ( φ ) 0 sin ( φ ) cos ( ξ ) cos ( φ ) cos ( ξ ) .
Let ρ represent the smartphone body frame x-axis gyro output, τ represent the smartphone body frame y-axis gyro output, and θ represent the body frame z-axis output. By taking the derivative of the roll, pitch, and yaw, the Euler angle rates are computed as
φ ξ ψ = ρ + τ sin ( φ ) tan ( ξ ) + θ cos ( φ ) tan ( ξ ) τ cos ( φ ) θ sin ( φ ) τ sin ( φ ) cos ( ξ ) + θ cos ( φ ) cos ( ξ ) .
Gimbal lock becomes a problem when using Euler angles and the above operation illustrates mathematically. When the pitch angle ξ approaches ± 90 , the matrix elements diverge to infinity because the zero in the denominator causes the filter to fail.
The quaternions data can be converted to Euler angles on the receiving end, and the exact equations for converting from quaternions to Euler angles depend on the order of rotations. The sensors move from the inertial navigational frame to the sensor body frame using the first yaw, then pitch, and finally roll. The Euler angles can be obtained from the quaternions, and this results in the following conversion equation:
φ ξ ψ = atan2 2 α σ 1 + σ 2 σ 3 , 1 2 σ 1 2 + σ 2 2 asin 2 α σ 2 σ 3 σ 1 atan2 2 α σ 3 + σ 1 σ 2 , 1 2 σ 2 2 + σ 3 2 .
To tackle the problem that arose due to the arctan and a r c s i n , function atan2 computes the principal value of the argument function applied to the complex number in the quaternion. The function atan2 value is in the range ( π , π ] , that is π < a t a n 2 ( y , x ) π . The body attitude matrix can be calculated by Euler angles φ , ξ , and ψ . By using the angular velocities of the body frame concerning the inertial navigation frame denoted in the smartphone body frame, the measure angular velocity can be calculated as explained in [48].

3.1.3. Orientation Estimation Based on UKF

In this study, the detailed explanation of orientation estimation based on UKF is presented as shown in Figure 3. As discussed in Section 3.1.1, in the proposed orientation estimation based on UKF, the prior gyros bias errors, and Euler angle errors are expressed as δ ϕ and δ ψ in the state vector of the proposed filter as x = δ ψ δ ϕ . Assuming δ ψ is small and the error quaternions e q is approximated as e q 1 δ ψ 2 The basic idea behind the use of the proposed filter is to use the quaternions as the global attitude representation and use a three-component state vector δ ψ for the local representation of attitude errors [11].
δ Ψ = δ Ψ . e
where δ ψ is the rotation error angle and e t = e x e y e z is the rotation axis. The product of estimated and error quaternion gives true quaternion q t = δ q ( δ ψ ) q ^ . Where e q = δ q ( δ ψ ) and the cross symbol shows quaternion multiplication [68]. The state vector in the proposed filter is chosen as δ ψ T δ ϕ T , here δ ψ is the error between the estimated gyroscope bias and true gyroscope bias.

3.1.4. Orientation Calculation System Model

The state equation for attitude estimation system is
x ˙ k = A k x k + E u k x k = δ ψ Δ Φ T
The process model is adopted as x k + 1 = I + A k × Δ t x k + u k , where u k is the noise vector, which refers to the noise related to the rotation error angle ζ δ Ψ ( t ) and ζ Δ Φ ( t ) is the noise error between true bias random walk and estimated bias random walk. A k is defined using the estimated
u k = ζ δ Ψ ( t ) ζ Δ Φ ( t ) , A k = w ^ b / n b I 3 × 3 0 3 × 3 0 3 × 3 , and E = I 3 × 3 0 3 × 3 0 3 × 3 I 3 × 3
rotation rate w ^ b / n b and ζ δ Ψ ( t ) ϵ R 3 and ζ Δ Φ ( t ) R 3 are process noise and are assumed to be a zero mean Gaussian white noise. Then, the process covariance matrix is
Q = E u k u k T   = c δ Ψ 2 0 3 × 3 0 3 × 3 ζ Δ Φ 2 .
The measurement equation is represented by, y = h ( q ) + a c c ˜ s b f m a g ˜ s b f T , where y is the measurement of the combination of accelerometer and magnetometer. Here a c ˜ c ˜ b R 3 and m a g ˜ b R 3 are output of accelerometer and magnetometer, η acc s b f and η magsbf are the measurement independent zero-mean Gaussian white-noise and can be expressed as the true magnetic and gravity vector m n and g n .
a c c ˜ s b f = e q q ^ g i n f q ^ e q + a c c s b f + η a c c s b f
m a g ˜ s b f = e q q ^ m i n f q ^ e q + a c c s b f + η m a g s b f
The variance of measurement noise is η a c c s b f 2 and η m a g s b f 2 and its covariance matrix expressed as M R = η a c c s b f 2 × I 3 × 3 0 3 × 3 0 3 × 3 η m a g s b f 2 . I 3 × 3 , and h ( q ) represents the nonlinear equations that convert the magnetometer reference vector r m a g ϵ R 3 and accelerometer reference vector r a c c ϵ R 3 from INF to the SBF. The values of r a c c and r m a g are constants whose specific values can be found using the method in [84].

3.1.5. Time and Sigma Points Update

For calculating the posterior first and second order statistics of a random variable, which undergoes the unscented transformation. By using a minimal set of deterministically chosen weighted sample points, the state distribution is again represented by a Gaussian random variable (GRV). Covariance and true mean completely capture the prior random variable by using the weighted sample points called sigma-points. In this case, the error state x contains the orientation information q and the gyro bias ϕ and has zero mean x ^ . The following scheme is used to calculate the sigma points ρ .
ρ j 1 = x ^ j 1 2 + λ K j 1 1 2 x ^ j 1 λ K j 1 1 2
where, λ represents the scaling parameter that shows the Sigma points spread around the column vectors of the covariance matrix K and x ^ .
λ = ( ι + γ ) 1 2 , and γ = μ ( ι + κ ) ι
whereas, the augmented state vector dimension is represented by l, μ = ( 10 3 , 1 ] , and K = 0 . To yield each point of a set, which is expressed through the Equation (52), and transformed samples ρ i , j j 1 = f ρ i , j 1 j 1 . Here the ith column of the matrix represent i. The prior estimates of covariance K x j prior and state x ^ j prior are given through the ρ as expressed in equation
x ^ j p r i o r = i = 0 2 l W i m ρ i , j j 1
K x j p r i o r = i = 0 2 l W i j ρ i , j j 1 x ^ j p r i o r 2 + Q j .
In the above two equations W i m and W i j are used to calculate the mean and covariance of the posterior ρ ′, respectively, as follows:
W 0 m = γ ( l + γ ) , W 0 j = γ ( l + γ ) + 1 μ 2 + β
W i m = 1 2 ( l + γ ) , W i j = 1 2 ( l + γ )
To determine posterior covariance, μ determines the spread of the ρ around x ^ k prior , where β accentuate the weighting on the zero ρ [85]. The value of optimal β is obtained from [86].

3.1.6. Measurement Update

Magnetic measurement and gravity vector are not good choices for the reckoning of the horizontal component of the state vector. Moreover, yaw correction is not possible by using a gravity vector. Due to the described issues and to ensure gravity correction, it does not act on the yaw estimate, and as magnetic anomalies only influence the pitch estimates and roll, we divide the measurement update into two steps. For the case of gravity vector measurement update:
M i , j j 1 a c c ˜ s b f = h a ρ i , j j 1
We set the third part of δ ψ to zero after the first update step, as q e , j x j = 0 and based on the update K the ρ should be recalculated. Similarly, the magnetic field vector measurement equation can be written as M i , j j 1 m = h m ρ i , j j 1 and the first two part of δ ψ are set to zero after the second update as q e , k [ 2 , 3 ] = 0 . In UKF compared to EKF, the system around its current state does not need to linearize.
To adaptively adjust the measurement covariance R, diagonal covariance inflation (CI) approach in [87] is implemented. In this approach, for the residual error ( y ˜ ) , the measurement update of the low-confidence hypothesis will inflate in all directions. The proposed covariance inflation approach always guaranteed the Mahalanobis distance r < 1 . The CI approach can resolve the inconsistency between the low-confidence hypothesis observation and the proposed filter prediction. The measurement update for the accelerometer and magnetometer is
y ˜ = q ^ g n q ^ a ˜ b
The determination of the error covariance R k is the main issue of implementing this method
R k a = c × y ˜ 2 + ζ a 2

3.2. Activity Detection Model Based on HMM

The observation model uses the inertial measurement (IMU) acceleration data received from the different activities performed by the person containing the smartphone. By performing various activities while holding a smartphone in a user′s hand, fingerprints are collected of each activity in an offline phase. Let ρ i , k , l be the measurements, having set M j collected in the various designated areas of the 4th floor of JEJU national university, concerning the k activities performed PA k . Whereas l { 0 , 1 , 2 , , M i 1 } . Once new IMU measurements set ρ t collected during random motion, containing all of the mentioned activities in Table 3. The model allocates specific evidence to each zone.
In previous research, the observation model′s role was to assign a weight w O , t ( . ) to each activity performed in the various dedicated zones Z i i { 0 , 1 , 2 , , M ( i 1 ) } for all measurements in ρ t . By modeling the activities based on the different values of the accelerations computed from various performed actions on the university floor, a distribution D ( . ) is constructed by the kernel density estimate.
D z i ( . ) = 1 M i l = 0 M i 1 1 h i 1 , 1 h i 1 , M P A k = 1 M P A K × ρ i , k , l / h i , k ,
To each PA in each zone K ( . ) is the kernel and h i , k is the bandwidth of the kernel. Due to the facility of analytical derivations, the Gaussian kernel is considered, and the shape of the kernel has no impact on the model [88].
K ( u ) = 1 ( 2 π ) 1 / 2 e 1 / 2 u 2
By maximizing the pseudo-likelihood leave-one-out cross-validation, the bandwidth of h i , k is estimated. h i , k = argmax h N L i , k ( h ) where N L i , k ( h ) is computed as,
N L i , k h i , k = 1 M i l = 0 M i 1 log l ˜ l K ρ i , k , l ρ i , k , l h i , k log M i 1 h i , k .
The allocation of weight by the observation model to each performed activity at any time t is computed as the output of the kernel density estimate of each zone followed by a normalization phase,
w 0 , t Z i   = D z i ρ t j = 0 M z 1 D z i ρ t .
In this activity detection approach, based on the hidden Markov model, the mobility model is constructed. To determine the confidence level that the sensor resides in each zone, the probability is assigned based on the measurements of the accelerometer and combined with the evidence given by the observation model. At first, we provide a general overview of the HMMs and the confidence-based zone estimation combined with the observation model.

3.2.1. Hidden Markov Models

A probabilistic model that can be used to represent observations, and these sequence of observations can either be independent, time-dependent, continuous, or discrete [89]. Let the S N HMM model be denoted by H, and the total states S = { S 1 , S 2 , , S N } . The objective of the Nth order HMM model is to determine the corresponding state sequence S = { S 1 , S 2 , , S α } , whenever the sequence of length α and R = { R 1 , R 1 , , R α } is given. For each present state, the probability of arriving at the next state is designated by the transition probability and termed as matrix A. The actual states are hidden from the observer and determine the likelihood that each type of observation is in each state by using observable data and termed as emission probabilities forming matrix B. Probabilities of starting at different states in HMM are represented as T. Based on the prior knowledge, it can be either random, any vector generated, or uniform. Thus any HMM can be represented as H = ( A , B , T ) . The transition probability from the state a to b can be denoted by P a b a , b { 1 , 2 , , S N } and forming the matrix A. The output probability distribution forming the matrix B, and can be represented as P ` a ( R ) , a { 1 , 2 , , S N } . The complete explanation is in [90].

3.2.2. Activity Detection Approach Architecture

In an indoor environment, the objective is to detect a change in the sensor state from one zone to another in a specific period. To determine the likelihood that the sensor has followed some trajectory, we use the HMMs. Since the states are hidden S = { S 1 , S 2 , , S α } , we can observe a sequence R = { R 1 , R 1 , , R α } , corresponding to a vector of acceleration magnitude measurements at each state. To observe the sequence R, we are interested in determining the probability P ( R | H ) . The probability obtained by the observation model is combined with P ( R | H ) to determine a confidence level of having the accelerometer sensor values residing in each zone. The transition between two zones Z i to Z j can be represented by S N state HMM H i , j , whereas a set of HMMs denoted as H i , j , i , j { 1 , 2 , , M z } . In each transition region, the number of states chosen by the user is represented as S N .
Figure 4 shows the transition region between each pair of neighboring zones in the offline phase. This region is divided into the number of states chosen by the user in each transition region. In each transition region, Γ = S N × σ a c c m a g measurements were gathered. Random selections of measurements from each state made the change in the frequency of the accelerometer values. Every kind of variation in the accelerometer values is considered as a database for each HMM. For each HMM H i , j = ( A , B , Γ ) , the parameters are calculated as follows,
  • Except for the first and the last state, where there are only two options, the accelerometer sensor values can move to the state upfront, behind, or retain their positions. The transition matrix A S N × S N .
  • The activity detection model of each sequence is computed by modeling the offline collected accelerometer sensor measurements of each sequence with the multi-dimensional distribution P a ( R ) = Q Γ ( P a ) , j { 1 , 2 , , M z } . For example, to model observation ρ a using the accelerometer sensor measurements Γ for all the PAs, the distribution Q Γ ( ρ a ) which is the output of the distribution Q(.) is used.
  • The vector T is defined as 1 S N , . . . , 1 S N , unless information of prior knowledge is given regarding the starting of the state vector.

3.2.3. Weight Assignment

The aim is to evaluate the probability of observing the sequence P ( R | H ) , given an observation R and S N state HMM model H. When we know the parameters of the HMM, this is a problem for evaluating the observed sequence. For the evaluation purpose of P ( R | H ) , it can be broken down as follows. We can compute the joint probability of the state sequence and the observed sequence, given a state sequence S = { S 1 , S 2 , , S α } , and the range of α values in different zones are α 1 α o α 2 , α 2 α o α 3 , α 3 α o α 4 , α 4 α o α 5 , α 5 α o α 6 ,
P ( R , S | H ) = P ( R | S , ) × P ( S | H )
In (30) is the product of the probability of the state sequence S given the model H and the likelihood of the observation sequence R given the state sequence S. The first term is obtained from the activity detection matrix B as follows,
P R α i H   = α = 1 α i a = 1 α i P ` s a R a
From the transition matrix A, the second term is obtained as,
P ( S H ) = a = 1 α i P s a 1 s a R a
By taking the summation of P ( R , S | H ) over all possible state sequences S N , we can then derive P R | H [91],
P ( R H ) = For all S P ( R , S H ) = For all S a = 1 α i P s a 1 s a P ` s a R a
The computational cost and feasibility of the system depend on the range of α . To obtain the probability P R | H and reduces the computational burden, a forward–backward algorithm can be used. Thus, (33) can be transformed as
P ( R H ) = y = 1 S N P R 1 , R 2 , × , R a , s a = P / H · P R a + 1 , R a + 2 , , R α i , s a = P ` , H ) g a ( P ` ) = P R 1 , , R a , s a = P ` H
h a ( P ` ) = P R a + 1 , , R α s a = P ` , H
The probabilities g a ( P ` ) and h a ( P ` ) mentioned in (35) can be recursively computed; therefore, the probability P R | H is given by,
P ( R H ) = P ` S N g a ( P ` ) h a ( P ` ) .
In the (36), when a transition between Z i to Z j took place, the objective of the proposed HMM-based activity detection model is to assign evidence. Each HMM H i , j allocate a likelihood based on a sequence R = { R 1 , R 1 , , R α } . For each HMM H i , j , the probabilities P R | H i , j , i , j { 1 , 2 , , M z } are computed. Based on that, the probabilities of the transitions between different zones are calculated. The probability is zero where no transition is possible. The coefficient of transition c i , j , i , j { 1 , 2 , , M z } between zones Z i to Z j is as follows,
c i , j =   P R H i , j , if i j 1 i = 1 M Z P R H i , j , if i = j .
Probabilities that the sensor moves from Z i to Z j are a complement to the probabilities where the likelihood for transition is zero. The calculation for the evidence w M , t . is as follows,
w M , t Z i   = j = 1 M z w O , t 1 Z j   ×   c i , j .
The weight associated with the observation model O ( . ) is w O , t 1 . The coefficient c i , j will be large if there is no transition Z i to Z j . All coefficient c i , j values in the case for i = j will be significant. This problem does not cause any issue if we put the values of coefficients in the above equation and, thus, evidence is based on the observation model w O , t 1 Z j .

3.2.4. Zone-Based Confidence Estimation

The evidence was allocated by the mobility model and the observation model combined to get the confidence C t ( . ) . The confidence level shows the zones based on the accelerometer sensor values.
C t Z i   = w 0 , t Z i × w M , t Z i x = 1 M z w 0 , t Z x × w M , t Z x
Based on the accelerometer sensor values, the zone with the highest confidence level chosen is shown in (39).

3.3. Pedestrian Dead Reckoning

The zero-velocity information is effectual for the error correction because of the sensor drift and fast accumulation of the positioning error. The velocity and angular velocity are almost zero when the pedestrian′s foot is totally on the ground. For that purpose, the PDR system based on HMM and ZVU algorithms is introduced. According to the accelerometer and gyroscope readings, rules are defined based on the threshold for ZVU detectors [92]. This method ignores the sensor measurement fluctuations and uses an instantaneous sample that only gives the precise phase judgment. To recognize the phase, the following is used: O b s =   o b s 1 , o b s 2 , , o b s k . To determine the observation o b s k at k time, stance, and swing phase, two indicators are deployed. The accelerometer measurement is constant in the stance phase, the angular rate approximates to zero, and local gravity is approximately equal to the phase magnitude. Therefore, the observation is defined as o b s k = Z 1 Z 2 , whereas
Z 1 =   a ˜ b g   < T H 1
Z 2 =   w ˜ b   < T H 1
where o b s k =   0 , 1 , T H 1 and T H 2 are thresholds. Thresholds are set empirically based on Z 1 and Z 2 calculated from the static test. To classify the observation into stance and swing, a long series of observations are given. To yield better recognition, the HMM is adopted, and to represent stance and swing, we use two HMMs, respectively. The calculation of the observations under each model and their conditional probability from the given observation sequence suggests the walking phase is the maximum probable model. For each HMM, the hidden state is assumed binary s = [ 0 , 1 ] . The output probability distribution d, which is B = b j ( k ) and state transition probability distribution A = a i j are the two elements.
B = P ( o t + 1 = k | s t = j )
and HMM is defined as ϵ = ( A , B ) , and the parameters A and B are determined by using [57]. Partial observation sequence o b s 1 , o b s 2 , , o b s t , ϵ being in state i at time t, and the forward probability is the probability of the HMM and it is shown in (43) as below,
μ t ( i ) = P o b s 1 , o b s 2 , , o b s T , | s t = i , ϵ
From t + 1 to the end, backward probability is the partial observation sequence probability, o b s t + 1 , o b s t + 2 , , o b s T , given the state s t = i and the model threshold.
Φ t ( i ) = P o b s t + 1 , o b s t + 2 , , o b s T s t = i , ϵ
Given an observation history O b s and HMM ϵ n to find new values of ϵ n + 1 , such that probability P O b s | ϵ n + 1 P ( O b s | ϵ n ) . From the state i we estimate the expected number of transitions based on the changing values of accelerometer sensor values as t = 1 T λ t i and t = 1 T 1 κ i , j from state i to j. The complete derivation procedure to estimate the new model parameters in the last step can be found in [77]. The algorithm for the observation sequence—the maximum probable model as the walking phase having estimated parameters of HMM. a r g k m a x P ( ϵ k | O b s ) where k = 0   o r   1 . Here, ϵ 1 represents the stance model, and ϵ 0 represents the swing model. By using the following equation during the swing phase, the velocity v n and the position p n are estimated by using the HMM-based ZVU algorithm.
a c c k n = q ^ k a c c ˜ c k b q ^ k g n
velocity k n = velocity k 1 n + a c c k n Δ t
position k n = position k 1 n + velocity k 1 n Δ t + 1 2 a c c k n Δ t 2
The sampling interval of the inertial sensors is t and g n and the gravity vector in inertial navigational frame { i n f } is g n .

4. Compensation Mechanism Based on AWCLA

In the case for the compensation mechanism based on AWCLA, we used iBeacon Estimote version Bluetooth 4.0 smart as a fixed device, and its detail is mentioned in Table 4. A 32-bit ARM® Cortex M0 is a small computer accompanied by a temperature sensor and accelerometer. Bluetooth low energy beacon uses ultra-high 2.4 GHz radio frequency. The CR2477 battery power source is used to power the BLE estimate for three years if used in the default condition. The range of the ideal Beacon is around 70 m, and in an indoor environment where signals can interfere, diffracted, or be absorbed by the walls and human body, the range is reduced to 30–40 m. The iBeacon sent information in an advertisement packet containing RSSI values, advertising intervals, measured power, and broadcasting power.

4.1. Kalman Filter Based RSSI Measurements Filtering

Figure 5 shows the distance computation between the object and Bluetooth low-energy beacons, which is used for calculating the position of an indoor object. Received signals from the beacons are used for the calculation of distance. To smooth RSSI signals, we used the proposed KF process and measurement model. The distance computing model and approach for RSSI estimation are presented. The distance output from iBeacons and the received RSSI measurements have suffered from high distance errors and high noise levels in the indoor environment. Various localization algorithms have been proposed to decrease the position error and enhance the accuracy when using the distance values based on the beacon output signals. However, still, the error is too high, and the localization accuracy is low. In this paper, indoor positioning accuracy and the distance error were improved using the proposed enhanced PDR-BLE compensation mechanism based on HMM and AWCLA for improving indoor localization.

4.2. Path-Loss Model-Based Measuring Distance

The nature of the medium and the distance are factors that cause an attenuation when wireless signals are transmitted. The signal is reflected, diffracted, refracted, and scattered when experiencing objects during transmission. In the case of LOS or NLOS, direct attenuated signal is due to other physical effects and indirect attenuated signals such as refraction, reflection, scattering, and diffraction [93]. In the simplest path loss model, there is no multi-path components and signal strength decreases by 1 d 1 .The amount of power transmitted compared to the power received is calculated using Friis free space equation [94].
received P = transmitted P T x G R x G λ ` 2 ( 4 π D ) 2 .
The path loss is expressed in dB and it takes place exponentially with distance as shown in Equation (49)
P l o s s d   = P l o s s d 0   +   10 n l o g ( d d 0 ) .
The relation between distance and RSSI in [80] can be described by the log-distance path loss model.
R S S I = 10 n l o g 10 d d 0 + r 0
The above equation can be rewritten as:
d = 10 ( ( T x s R S S I ) 10 n )
where, the strength of the transmitted signal is T x s . The process model for smoothing RSSI using the Kalman Filter is shown below in Equation (52):
x t + 1 = A x t 1 + B u t + w t
The relationship is modeled through matrices A and B, and it is among the control unit, current state, and previous state. At time step t, the state of interest is x t + 1 , whereas the previous state is x t 1 , w t is the process noise, and the control input is u t . The KF based observation model is expressed as:
m t = T X t + v t
where, at time step t m t is the measurement, the transformation matrix is represented as T, and noise measurement is v t .
Likewise, the steps update and prediction based on the Kalman filter are as follows
x ^ t = x ^ t 1 + B u t ( S t a t e p r e d i c t i o n )
P ^ t = A P t 1 A T + Q ( E r r o r C o v a r i a n c e )
G K = P t T T T P t T T + K 1 ( Gain Calculation )
x ^ t = x ^ t + G t m t G t T P t ( Estimate update )
P t = I G t T P t ( Error covariance update )
We define RSSI signals as the state of interest x t . For certain time frames, the mobile and position are set as static; hence, the RSSI measurements in that time frame remain constant, and the rest of the parameters are taken as process noise. The model can be constructed by setting A to an identity matrix and ignoring control input u t .
The RSSI estimation is computed in three steps. Step 1: x t = R S S I t . Step 2: x ˙ t = A x t + w t (Kalman filter process model). Step 3: r s s i m = T x t + V t , observation are designed by using the received RSSI measurements and the relationship between the state of interest. For the state of interest updates and the KF, we use a time step from t 1 to t, variance from the time step t 1 to t, and Kalman Gain (KG).

4.3. Position Estimation Using Beacon Weights

To find the mobile position the centroid location algorithm uses, while using the weight of each Beacon, the weighted centroid location WCL estimates the mobile location. In this paper, we explored the Beacon′s importance in terms of weight to estimate the mobile position based on CLA by using the deployed beacons. The accuracy of the centroid localization algorithm is poor, so different modifications are proposed to decrease the position error. To improve the object′s position, the proximity between the mobile devices and the Beacons are considered in terms of weights for each beacon. The relationship between the weight and distance is directly proportional, while the impacts of propinquity between the mobile devices and the beacons are inversely proportional. Based on (59), the value of Beacon weight is calculated using equation
w i j = 1 ( d ^ i j ) g ,
where the estimated distance between the mobile device and beacon is denoted by d i j and the adjustable degree depends on the environments, and it is referred to g. To estimate the unknown mobile position, the weighted centroid localization algorithm uses Equations (60) and (61) based on the known Beacon position.
x ^ = i = 1 n w i × x i i = 1 n w i
y ^ = i = 1 n w i × x i i = 1 n w i
Here x ^ , y ^ are the estimated x and y coordinate. The weight of each Beacon calculates using the signal power per Equation (62)
w i j = r e f x , y   ×   10 R S S I 20 g
Calculations of smartphone locations in indoor surroundings based on KF, which integrates the smoothed RSSI measurements based on the beacon weight. In the proposed algorithm based on KF, RSSI measurements are pre-processed and integrated. The proposed beacon-based localization eliminates noise and smooth RSSI values. By using the estimated filtered RSSI values, the distance between the deployed beacons and smartphones is calculated. The strength of the received RSSI signal is directly proportional to the power delivered to the beacon. The calculation of the actual distance between the deployed beacons and smartphones by using centroid points of beacons.
d a c t u a l n = ( x n x 0 2 +   y n y 0 2 ) 1 2 ( n = 1 , 2 , , m )
The error in distance is calculated using equation d n = d n d a c t u a l n ( n = 1 , 2 , , m ) . The position error between the BLE beacon and smartphone is denoted by d n . The estimated smartphone coordinates are calculated using weights of BLE beacons, and the average of the BLE beacons used to calculate the position. The estimated position of the smartphone is calculated as follows.
x ^ e s t = n = 1 m w n a v g ×   x c i j n = 1 m w n a v g ( i & j = a , b , c ) and i j
y ^ e s t = n = 1 m w n a v g ×   y c i j n = 1 m w n a v g ( i & j = a , b , c ) and i j
E p = x ^ e s t x 0 2 + y ^ e s t y 0 2 1 / 2
Figure 6 and Figure 7 shows the activities performed by an object in an indoor environment. In Figure 6, various performed activities are shown, which include working on a computer or idle activity, running activity, walking upstairs, walking on a plain surface, and writing on board. The change in the magnitude of accelerometer sensor values clearly illustrates the activities start and end times. It also shows how the change in the frequency also changes as the change in activity occurs. The high magnitude and high frequency in activity writing onboard show the frequent movement of the test object in an indoor environment. On the other hand, Figure 7 demonstrates the raw data information obtained from the IMU smartphone-based sensor.

5. Experimental Results and Discussion

Development Environment

Experiments were conducted on a Windows PC with 12GB RAM. A front end (desktop application) was developed using Java, and the clustering techniques were applied in python. Well-know python libraries, including NumPy, SkLearn, and Scipy, were used for clustering experiments. In addition, NCSS was used for the visualization of data in PC. Furthermore, the simulation time for acquiring data for every instance was one minute (60 s). The required software and hardware components are listed in Table 5.

6. Results and Discussion

To validate our enhanced PDR-BLE compensation mechanism based on HMM and AWCLA for improving indoor localization, the person moves in an indoor environment with a Bluetooth enabled smartphone. The mobile was tested in seven different locations. Actual smartphone coordinates were compared with the estimated positions. Seven Bluetooth low energy beacons with known coordinates named C 1 ( x 1 , y 1 ) , C 2 ( x 2 , y 2 ) , C n ( x n , y n ) ( n 1 , 2 , 6 ) placed in the entry and exit points of the fourth floor of Jeju National University, South Korea. To validate our approach, at eleven different locations, the position of the smartphone was calculated. The RSSI values of the BLE-beacon, as shown in the figure, were calculated in the android application. The positioning system in this paper is three-dimensional. In this paper, we considered two floors of Jeju National University engineering building 4. We used a 3D navigation approach to localize object movement in an indoor environment.
By using the Kalman filter in the proposed algorithm, the collected RSSI values were then smoothed, and for position estimation of the smartphone, the weight of each BLE-beacon was used. The figure shows various smartphone and deployed BLE beacon positions.

6.1. Error Reduction Using Kalman Filter in RSSI Measurement

To validate our KF approach mentioned in Section 4, RSSI measurements passed through KF to reduce errors. The result of smoothed RSSI values obtained after passing raw RSSI measurements through the Kalman filter from different smartphone locations is mentioned in Table 6. On separate entry and exit points of the floor, the estimated BLE-beacon RSSI values and raw BLE-beacon RSSI values are shown in Figure 8. The smoothed BLE-beacon RSSI values are further used to calculate the distance.

6.1.1. Comparison between BLE-Beacon, PDR and EPBCM Localization Algorithm

The estimated mobile positions using EPBCM algorithm, the BLE-beacon and PDR is given in Table 7. The combined plotting of EPBCM, PDR, and BLE-beacon-based localization at all tested mobile positions is shown in Figure 9. The EPBCM algorithm shows promising results when compared with other IPS, such as PDR and BLE-beacon-based systems.

6.1.2. EPBCM Algorithm Based Positioning

To validate the EPBCM localization algorithm, six mobile positions were chosen and compared with other estimated positions using different approaches. Figure 10 shows the actual position at six random mobile positions compared to their estimated location using EPBCM, PDR, and the BLE-beacon algorithm. The deviation of position obtained from the proposed EPBCM approach from the actual position is shown in Table 6, along with the coordinates of these locations and their errors.
The measurements of accelerometer, magnetometer, and gyroscope were used to track the position and orientation of an object moving in an indoor environment. Walking down two flights of stairs, trajectory is shown in Figure 11, whereas the count of steps in each flight is 13 steps.
The purpose of showing this result is to evaluate the performance of UKF-based orientation tracking and data collection from smartphone-based IMU sensors. The starting point is the mobile computing lab (MCL) situated on the fourth floor of the JNU, and the ending point is the end of two flights of stairs. However, the exact ground truth cannot be given, but the person′s orientation and activity can be determined. Compared to the flat ground, the error in stair walking is more significant. This is due to the fact that the calculations of vertical acceleration in stair walking has to be calculated for this scenario and it must include gravitational acceleration.
In this experiment, several pedestrian walking experiments were conducted in the engineering building of JNU, and the final results are shown in Figure 12. In addition, walking experiments were conducted to assess the performance further, and the smartphone′s position was compared with the various reference points at the path of the test subject. Figure 12a shows pedestrian walking experiment conducted on the fourth floor of Jeju National University. It is clearly seen that the localization trajectory based on the proposed EPBCM algorithm follows the ground truth values. Figure 12b shows the complete round trip foot trajectory of walking along a corridor, walking down two flights of stairs, containing multiple turns, and the total distance covered is around 220.35 m. The trajectory computed with the proposed algorithm is compared with the PDR localization algorithm and actual trajectory. The proposed localization algorithm shows a clear decrease in the drift from the actual path as compared to the PDR. To quantify the positioning accuracy, we adopted the maximum error and end-to-end error. For the evaluation of the proposed algorithm, we implemented three algorithms EPBCM, PDR, and BLE. EPBCM incorporates accelerometer magnitude HMM-based detection, and the other two are PDR and BLE-beacon-based localization algorithms.

7. Conclusions

In this study, an EPBCM based localization algorithm was developed to estimate the position of an object in an indoor environment. The proposed system is a combination of two localization algorithms—PDR and BLE-beacons. In the proposed position estimation module, orientation is estimated using the unscented Kalman filter and HMM-based activity detection by considering the varying measurements of the accelerometer sensor. In this paper, the BLE-beacon-based localization algorithm is used as a compensation algorithm. In this compensation model, the path-loss model is used for distance measurement. The Kalman filter is used for noise elimination, smoothing RSSI measurements, and integrates raw BLE-beacons measurements to reduce the positioning error. The position estimation combinator is designed to combine the position coordinates of the two localization algorithms and get the enhanced position, containing less error. For comparative analysis, we compare the HMM-based activity detection approach results with the K-mean clustering technique. We also compare the three localization algorithm results, showing the proposed indoor positioning system containing the least error. It also shows that the proposed algorithm deviation from the actual location is the minimum. The walking scenario experimental results show that the proposed EPBCM based on HMM and AWCLA is feasible for the indoor positioning system. At some points, the positioning error is tiny, although to maintain a high accuracy level, more beacon deployment must be required to get more compensation in error at different mobile locations.

Author Contributions

Data curation, H.J.; Formal analysis, F.J.; Funding acquisition, D.-H.K.; Investigation, F.J.; Methodology, D.-H.K.; Software, F.Q.; Supervision, D.-H.K.; Validation, H.J; Visualization, H.J.; Writing—original draft, F.J., H.J and F.Q.; Writing—review & editing, F.J., H.J., F.Q. and D.-H.K. All authors have read and agreed to the published version of the manuscript.

Funding

This research was supported by the MSIT(Ministry of Science and ICT), Korea, under the ITRC(Information Technology Research Center) support program(IITP-2019-2016-0-00313) su-pervised by the IITP(Institute for Information & communications Technology Planning & Evalu-ation), and this research was supported by Energy Cloud R&D Program through the National Research Foundation of Korea (NRF) funded by the Ministry of Science, ICT (2019M3F2A1073387), Any correspondence related to this paper should be addressed to DoHyeun Kim.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Ometov, A.; Shubina, V.; Klus, L.; Skibińska, J.; Saafi, S.; Pascacio, P.; Flueratoru, L.; Gaibor, D.Q.; Chukhno, N.; Chukhno, O.; et al. A Survey on Wearable Technology: History, State-of-the-Art and Current Challenges. Comput. Netw. 2021, 193, 108074. [Google Scholar] [CrossRef]
  2. Subedi, S.; Pyun, J.Y. A Survey of Smartphone-Based Indoor Positioning System Using RF-Based Wireless Technologies. Sensors 2020, 20, 7230. [Google Scholar] [CrossRef] [PubMed]
  3. Hofmann-Wellenhof, B.; Lichtenegger, H.; Collins, J. Global Positioning System: Theory and Practice; Springer Science & Business Media: Berlin/Heidelberg, Germany, 2012. [Google Scholar]
  4. Catania, P.; Comparetti, A.; Febo, P.; Morello, G.; Orlando, S.; Roma, E.; Vallone, M. Positioning Accuracy Comparison of GNSS Receivers Used for Mapping and Guidance of Agricultural Machines. Agronomy 2020, 10, 924. [Google Scholar] [CrossRef]
  5. Roberts, C.M. Radio frequency identification (RFID). Comput. Secur. 2006, 25, 18–26. [Google Scholar] [CrossRef] [Green Version]
  6. Zhao, H.; Yan, Y.; Shi, X. A Dynamic Localization Network for Regional Navigation under Global Navigation Satellite System Denial Environments; SAGE publisher: California, CA, USA, 2019. [Google Scholar]
  7. Ijaz, F.; Yang, H.K.; Ahmad, A.W.; Lee, C. Indoor positioning: A review of indoor ultrasonic positioning systems. In Proceedings of the 2013 15th International Conference on Advanced Communications Technology (ICACT), Pyeongchang, Korea, 27–30 January 2013; pp. 1146–1150. [Google Scholar]
  8. Fard, H.K.; Chen, Y.; Son, K.K. Indoor positioning of mobile devices with agile iBeacon deployment. In Proceedings of the 2015 IEEE 28th Canadian Conference on Electrical and Computer Engineering (CCECE), Halifax, NS, Canada, 3–6 May 2015; pp. 275–279. [Google Scholar]
  9. Alarifi, A.; Al-Salman, A.; Alsaleh, M.; Alnafessah, A.; Al-Hadhrami, S.; Al-Ammar, M.A.; Al-Khalifa, H.S. Ultra Wideband Indoor Positioning Technologies: Analysis and Recent Advances. Sensors 2016, 16, 707. [Google Scholar] [CrossRef]
  10. Uradzinski, M.; Guo, H.; Liu, X.; Yu, M. Advanced Indoor Positioning Using Zigbee Wireless Technology. Wirel. Pers. Commun. 2017, 97, 6509–6518. [Google Scholar] [CrossRef]
  11. Markley, F.L.; Crassidis, J.L. Attitude Control. In Fundamentals of Spacecraft Attitude Determination and Control; Markley, F.L., Crassidis, J.L., Eds.; Space Technology Library; Springer: New York, NY, USA, 2014; pp. 287–343. [Google Scholar]
  12. Obeidat, H.; Shuaieb, W.; Obeidat, O.; Abd-Alhameed, R. A review of indoor localization techniques and wireless technologies. Wirel. Pers. Commun. 2021, 119, 289–327. [Google Scholar] [CrossRef]
  13. Chen, Y.; Pan, Q.; Liang, Y.; Hu, Z. AWCL: Adaptive weighted centroid target localization algorithm based on RSSI in WSN. In Proceedings of the 2010 3rd International Conference on Computer Science and Information Technology, Chengdu, China, 9–11 July 2010; Volume 9, pp. 331–336. [Google Scholar]
  14. Mora-Becerra, F.J. Error Mitigation in RSSI-Based Fingerprinting Localization Using Multiple Communication Channels. Master′s Thesis, University of Nebraska-Lincoln, Lincoln, NE, USA, 2016. [Google Scholar]
  15. Jian Yin, L. A New Distance Vector-Hop Localization Algorithm Based on Half-Measure Weighted Centroid. Mob. Inf. Syst. 2019, 2019, e9892512. [Google Scholar] [CrossRef]
  16. Shi, Y.; Shi, W.; Liu, X.; Xiao, X. An RSSI Classification and Tracing Algorithm to Improve Trilateration-Based Positioning. Sensors 2020, 20, 4244. [Google Scholar] [CrossRef]
  17. Qiu, S.; Wang, Z.; Zhao, H.; Qin, K.; Li, Z.; Hu, H. Inertial/magnetic sensors based pedestrian dead reckoning by means of multi-sensor fusion. Inf. Fusion 2018, 39, 108–119. [Google Scholar] [CrossRef] [Green Version]
  18. Townsend, K.; Cufí, C.; Akiba; Davidson, R. Getting Started with Bluetooth Low Energy: Tools and Techniques for Low-Power Networking; O′Reilly Media, Inc.: Sebastopol, CA, USA, 2014. [Google Scholar]
  19. Arun, M.; Sivasankari, N.; Vanathi, D.P.T.; Manimegalai, D.P. Analysis of Average Weight Based Centroid Localization Algorithm for Mobile Wireless Sensor Networks; Research India Publications: Delhi, India, 2017; Volume 10, pp. 757–780. [Google Scholar]
  20. Iqbal, N.; Rizwan, A.; Khan, A.N.; Ahmad, R.; Kim, B.W.; Kim, K.; Kim, D.H. Boreholes Data Analysis Architecture Based on Clustering and Prediction Models for Enhancing Underground Safety Verification. IEEE Access 2021, 9, 78428–78451. [Google Scholar] [CrossRef]
  21. Rizwan, A.; Iqbal, N.; Ahmad, R.; Kim, D.H. WR-SVM Model Based on the Margin Radius Approach for Solving the Minimum Enclosing Ball Problem in Support Vector Machine Classification. Appl. Sci. 2021, 11, 4657. [Google Scholar] [CrossRef]
  22. Imran; Ahmad, S.; Kim, D.H. Quantum GIS Based Descriptive and Predictive Data Analysis for Effective Planning of Waste Management. IEEE Access 2020, 8, 46193–46205. [Google Scholar] [CrossRef]
  23. Qayyum, F.; Afzal, M. Identification of important citations by exploiting research articles′ metadata and cue-terms from content. Scientometrics 2018, 118, 21–43. [Google Scholar] [CrossRef]
  24. Khan, A.N.; Iqbal, N.; Rizwan, A.; Ahmad, R.; Kim, D.H. An Ensemble Energy Consumption Forecasting Model Based on Spatial-Temporal Clustering Analysis in Residential Buildings. Energies 2021, 14, 3020. [Google Scholar] [CrossRef]
  25. Ahmed, U.; Zafar, L.; Qayyum, F.; Arshad Islam, M. Irony Detector at SemEval-2018 Task 3: Irony Detection in English Tweets using Word Graph. In Proceedings of the 12th International Workshop on Semantic Evaluation, New Orleans, LA, USA, 5–6 June 2018; Association for Computational Linguistics: New Orleans, LA, USA, 2018; pp. 581–586. [Google Scholar]
  26. Zaabar, B.; Cheikhrouhou, O.; Jamil, F.; Ammi, M.; Abid, M. HealthBlock: A secure blockchain-based healthcare data management system. Comput. Netw. 2021, 200, 108500. [Google Scholar] [CrossRef]
  27. Ahmad, S.; Ali, J.; Jamil, F.; Whangbo, T.K.; Kim, D. Complex Problems Solution as a Service Based on Predictive Optimization and Tasks Orchestration in Smart Cities; Tech Science Press: Henderson, NV, USA, 2021. [Google Scholar]
  28. Ibrahim, M.; Imran, M.; Jamil, F.; Lee, Y.J.; Kim, D.H. EAMA: Efficient adaptive migration algorithm for cloud data centers (CDCs). Symmetry 2021, 13, 690. [Google Scholar] [CrossRef]
  29. Jamil, F.; Kim, D. Enhanced Kalman filter algorithm using fuzzy inference for improving position estimation in indoor navigation. J. Intell. Fuzzy Syst. 2021, 40, 1–15. [Google Scholar]
  30. Iqbal, N.; Ahmad, R.; Jamil, F.; Kim, D.H. Hybrid features prediction model of movie quality using Multi-machine learning techniques for effective business resource planning. J. Intell. Fuzzy Syst. 2021, 40, 1–22. [Google Scholar]
  31. Mehmood, F.; Ahmad, S.; Ullah, I.; Jamil, F.; Kim, D. Towards a Dynamic Virtual iot Network Based on User Requirements; Tech Science Press: Henderson, NV, USA, 2021. [Google Scholar]
  32. Jamil, F.; Qayyum, F.; Alhelaly, S.; Javed, F.; Muthanna, A. Intelligent Microservice Based on Blockchain for Healthcare Applications. CMC-Comput. Mater. Contin. 2021, 69, 2513–2530. [Google Scholar] [CrossRef]
  33. Ali, A.; Iqbal, M.M.; Jamil, H.; Qayyum, F.; Jabbar, S.; Cheikhrouhou, O.; Baz, M.; Jamil, F. An Efficient Dynamic-Decision Based Task Scheduler for Task Offloading Optimization and Energy Management in Mobile Cloud Computing. Sensors 2021, 21, 4527. [Google Scholar] [CrossRef] [PubMed]
  34. Bin Waheed, M.H.; Jamil, F.; Qayyum, A.; Jamil, H.; Cheikhrouhou, O.; Ibrahim, M.; Bhushan, B.; Hmam, H. A New Efficient Architecture for Adaptive Bit-Rate Video Streaming. Sustainability 2021, 13, 4541. [Google Scholar] [CrossRef]
  35. Jamil, F.; Kahng, H.K.; Kim, S.; Kim, D.H. Towards Secure Fitness Framework Based on IoT-Enabled Blockchain Network Integrated with Machine Learning Algorithms. Sensors 2021, 21, 1640. [Google Scholar] [CrossRef] [PubMed]
  36. Jamil, F. Energy Service Architecture based on SECaaS and AIoT for Energy Trading and Resource Management in Smart Nanogrid. Ph.D. Thesis, JEJU National University, Jeju-do, Korea, 2021. [Google Scholar]
  37. Ahmad, S.; Ullah, I.; Jamil, F.; Kim, D. Toward the Optimal Operation of Hybrid Renewable Energy Resources in Microgrids. Energies 2020, 13, 5482. [Google Scholar] [CrossRef]
  38. Jamil, F.; Kim, D. Payment mechanism for electronic charging using blockchain in smart vehicle. Korea 2019, 30, 31. [Google Scholar]
  39. Jamil, F.; Hang, L.; Kim, K.; Kim, D. A novel medical blockchain model for drug supply chain integrity management in a smart hospital. Electronics 2019, 8, 505. [Google Scholar] [CrossRef] [Green Version]
  40. Jamil, F.; Ahmad, S.; Iqbal, N.; Kim, D.H. Towards a remote monitoring of patient vital signs based on IoT-based blockchain integrity management platforms in smart hospitals. Sensors 2020, 20, 2195. [Google Scholar] [CrossRef] [Green Version]
  41. Jamil, F.; Iqbal, M.A.; Amin, R.; Kim, D. Adaptive thermal-aware routing protocol for wireless body area network. Electronics 2019, 8, 47. [Google Scholar] [CrossRef] [Green Version]
  42. Ahmad, S.; Jamil, F.; Khudoyberdiev, A.; Kim, D. Accident risk prediction and avoidance in intelligent semi-autonomous vehicles based on road safety data and driver biological behaviours. J. Intell. Fuzzy Syst. 2020, 38, 4591–4601. [Google Scholar] [CrossRef]
  43. Jamil, F.; Cheikhrouhou, O.; Jamil, H.; Koubaa, A.; Derhab, A.; Ferrag, M.A. PetroBlock: A blockchain-based payment mechanism for fueling smart vehicles. Appl. Sci. 2021, 11, 3055. [Google Scholar] [CrossRef]
  44. Kunhoth, J.; Karkar, A.; Al-Maadeed, S.; Al-Ali, A. Indoor positioning and wayfinding systems: A survey. Hum.-Centric Comput. Inf. Sci. 2020, 10, 18. [Google Scholar] [CrossRef]
  45. Mendoza-Silva, G.M.; Torres-Sospedra, J.; Huerta, J. A Meta-Review of Indoor Positioning Systems. Sensors 2019, 19, 4507. [Google Scholar] [CrossRef] [Green Version]
  46. Marques, J.P.P.; Cunha, D.C.; Harada, L.M.; Silva, L.N.; Silva, I.D. A cost-effective trilateration-based radio localization algorithm using machine learning and sequential least-square programming optimization. In Computer Communications; Elsevier: Amsterdam, The Netherlands, 2021. [Google Scholar]
  47. Beauregard, S. Omnidirectional Pedestrian Navigation for First Responders; IEEE: Piscataway, NJ, USA, 2007; pp. 33–36. [Google Scholar]
  48. Kok, M.; Hol, J.D.; Schön, T.B. Using Inertial Sensors for Position and Orientation Estimation. Found. Trends Signal Process. 2017, 11, 1–153. [Google Scholar] [CrossRef] [Green Version]
  49. Navigation Using Inertial Sensors [Tutorial]. Available online: https://ieeexplore.ieee.org/document/7081494 (accessed on 1 February 2015).
  50. Jiménez, A.R.; Seco, F.; Zampella, F.; Prieto, J.C.; Guevara, J. PDR with a Foot-Mounted IMU and Ramp Detection. Sensors 2011, 11, 9393–9410. [Google Scholar] [CrossRef] [Green Version]
  51. Lee, G.T.; Seo, S.B.; Jeon, W.S. Indoor Localization by Kalman Filter based Combining of UWB-Positioning and PDR. In Proceedings of the 2021 IEEE 18th Annual Consumer Communications Networking Conference (CCNC), Las Vegas, NV, USA, 9–12 January 2021; pp. 1–6. [Google Scholar]
  52. Sabatini, A.M. Estimating Three-Dimensional Orientation of Human Body Parts by Inertial/Magnetic Sensing. Sensors 2011, 11, 1489–1525. [Google Scholar] [CrossRef] [Green Version]
  53. Wang, Y.; Soltani, M.; Hussain, D.M.A. An Attitude Heading and Reference System for Marine Satellite Tracking Antenna. IEEE Trans. Ind. Electron. 2017, 64, 3095–3104. [Google Scholar] [CrossRef]
  54. Tong, X.; Li, Z.; Han, G.; Liu, N.; Su, Y.; Ning, J.; Yang, F. Adaptive EKF Based on HMM Recognizer for Attitude Estimation Using MEMS MARG Sensors. IEEE Sensors J. 2018, 18, 3299–3310. [Google Scholar] [CrossRef]
  55. Sabatelli, S.; Galgani, M.; Fanucci, L.; Rocchi, A. A Double-Stage Kalman Filter for Orientation Tracking With an Integrated Processor in 9-D IMU. IEEE Trans. Instrum. Meas. 2013, 62, 590–598. [Google Scholar] [CrossRef]
  56. Zhang, R.; Xia, W.; Jia, Z.; Shen, L. The indoor localization method based on the integration of RSSI and inertial sensor. In Proceedings of the 2014 IEEE 3rd Global Conference on Consumer Electronics (GCCE), Tokyo, Japan, 7–10 October 2014; pp. 332–336. [Google Scholar]
  57. Skog, I.; Handel, P.; Nilsson, J.O.; Rantakokko, J. Zero-Velocity Detection—An Algorithm Evaluation. IEEE Trans. Biomed. Eng. 2010, 57, 2657–2666. [Google Scholar] [CrossRef]
  58. Trabelsi, D.; Mohammed, S.; Chamroukhi, F.; Oukhellou, L.; Amirat, Y. An Unsupervised Approach for Automatic Activity Recognition Based on Hidden Markov Model Regression. IEEE Trans. Autom. Sci. Eng. 2013, 10, 829–835. [Google Scholar] [CrossRef] [Green Version]
  59. Seitz, J.; Vaupel, T.; Meyer, S.; Boronat, J.G.; Thielecke, J. A Hidden Markov Model for pedestrian navigation. In Proceedings of the Navigation and Communication 2010 7th Workshop on Positioning, Dresden, Germany, 11–12 March 2010; pp. 120–127. [Google Scholar]
  60. Ryu, S.J.; Kim, J.H. Classification of long-term motions using a two-layered hidden Markov model in a wearable sensor system. In Proceedings of the 2011 IEEE International Conference on Robotics and Biomimetics, Karon Beach, Thailand, 7–11 December 2011; pp. 2975–2980. [Google Scholar]
  61. Ahmad, N.; Han, L.; Iqbal, K.; Ahmad, R.; Abid, M.A.; Iqbal, N. SARM: Salah activities recognition model based on smartphone. Electronics 2019, 8, 881. [Google Scholar] [CrossRef] [Green Version]
  62. Ma, H.; Wang, Y.; Wang, K.; Ma, Z. The Optimization for Hyperbolic Positioning of UHF Passive RFID Tags. IEEE Trans. Autom. Sci. Eng. 2017, 14, 1590–1600. [Google Scholar] [CrossRef]
  63. Ma, Y.; Wang, B.; Pei, S.; Zhang, Y.; Zhang, S.; Yu, J. An Indoor Localization Method Based on AOA and PDOA Using Virtual Stations in Multipath and NLOS Environments for Passive UHF RFID. IEEE Access 2018, 6, 31772–31782. [Google Scholar] [CrossRef]
  64. Huang, K.; He, K.; Du, X. A Hybrid Method to Improve the BLE-Based Indoor Positioning in a Dense Bluetooth Environment. Sensors 2019, 19, 424. [Google Scholar] [CrossRef] [Green Version]
  65. Ozer, A.; John, E. Improving the Accuracy of Bluetooth Low Energy Indoor Positioning System Using Kalman Filtering. In Proceedings of the 2016 International Conference on Computational Science and Computational Intelligence (CSCI), Las Vegas, NV, USA, 15–17 December 2016; pp. 180–185. [Google Scholar]
  66. Lee, M.S.; Ju, H.; Song, J.W.; Park, C.G. Kinematic Model-Based Pedestrian Dead Reckoning for Heading Correction and Lower Body Motion Tracking. Sensors 2015, 15, 28129–28153. [Google Scholar] [CrossRef] [Green Version]
  67. Wang, Y.; Yang, X.; Zhao, Y.; Liu, Y.; Cuthbert, L. Bluetooth positioning using RSSI and triangulation methods. In Proceedings of the 2013 IEEE 10th Consumer Communications and Networking Conference (CCNC), Las Vegas, NV, USA, 11–14 January 2013; pp. 837–842. [Google Scholar]
  68. Ji, M.; Kim, J.; Cho, Y.; Lee, Y.; Park, S. A novel Wi-Fi AP localization method using Monte Carlo path-loss model fitting simulation. In Proceedings of the 2013 IEEE 24th Annual International Symposium on Personal, Indoor, and Mobile Radio Communications (PIMRC), London, UK, 8–11 September 2013; pp. 3487–3491. [Google Scholar]
  69. Zhao, Y.; Li, X.; Wang, Y.; Xu, C.Z. Biased Constrained Hybrid Kalman Filter for Range-Based Indoor Localization. IEEE Sens. J. 2018, 18, 1647–1655. [Google Scholar] [CrossRef]
  70. Wang, X.; Gao, L.; Mao, S.; Pandey, S. CSI-Based Fingerprinting for Indoor Localization: A Deep Learning Approach. IEEE Trans. Veh. Technol. 2017, 66, 763–776. [Google Scholar] [CrossRef] [Green Version]
  71. Gu, F.; Khoshelham, K.; Yu, C.; Shang, J. Accurate Step Length Estimation for Pedestrian Dead Reckoning Localization Using Stacked Autoencoders. IEEE Trans. Instrum. Meas. 2019, 68, 2705–2713. [Google Scholar] [CrossRef]
  72. Wagstaff, B.; Kelly, J. LSTM-Based Zero-Velocity Detection for Robust Inertial Navigation. In Proceedings of the 2018 International Conference on Indoor Positioning and Indoor Navigation (IPIN), Nantes, France, 24–27 September 2018; pp. 1–8. [Google Scholar]
  73. Lan, K.C.; Shih, W.Y. On Calibrating the Sensor Errors of a PDR-Based Indoor Localization System. Sensors 2013, 13, 4781–4810. [Google Scholar] [CrossRef] [Green Version]
  74. Bao, H.; Wong, W.C. A Novel Map-Based Dead-Reckoning Algorithm for Indoor Localization. J. Sens. Actuat. Netw. 2014, 3, 44–63. [Google Scholar] [CrossRef]
  75. Mikov, A.; Moschevikin, A.; Fedorov, A.; Sikora, A. A localization system using inertial measurement units from wireless commercial hand-held devices. In Proceedings of the International Conference on Indoor Positioning and Indoor Navigation, Montbeliard, France, 28–31 October 2013; pp. 1–7. [Google Scholar]
  76. Jamil, F.; Kim, D.H. Improving Accuracy of the Alpha-Beta Filter Algorithm Using an ANN-Based Learning Mechanism in Indoor Navigation System. Sensors 2019, 19, 3946. [Google Scholar] [CrossRef] [Green Version]
  77. Jamil, F.; Iqbal, N.; Ahmad, S.; Kim, D.H. Toward Accurate Position Estimation Using Learning to Prediction Algorithm in Indoor Navigation. Sensors 2020, 20, 4410. [Google Scholar] [CrossRef]
  78. Tian, Q.; Salcic, Z.; Wang, K.I.K.; Pan, Y. An enhanced pedestrian dead reckoning approach for pedestrian tracking using smartphones. In Proceedings of the 2015 IEEE Tenth International Conference on Intelligent Sensors, Sensor Networks and Information Processing (ISSNIP), Singapore, 7–9 April 2015; pp. 1–6. [Google Scholar]
  79. Jimenez Ruiz, A.R.; Seco Granja, F.; Prieto Honorato, J.C.; Guevara Rosas, J.I. Accurate Pedestrian Indoor Navigation by Tightly Coupling Foot-Mounted IMU and RFID Measurements. IEEE Trans. Instrum. Meas. 2012, 61, 178–189. [Google Scholar] [CrossRef] [Green Version]
  80. Chirakkal, V.V.; Park, M.; Han, D.S. Exploring Smartphone-Based Indoor Navigation: A QR Code Assistance-Based Approach. IEIE Trans. Smart Process. Comput. 2015, 4, 173–182. [Google Scholar] [CrossRef]
  81. Meliones, A.; Sampson, D. Blind MuseumTourer: A System for Self-Guided Tours in Museums and Blind Indoor Navigation. Technologies 2018, 6, 4. [Google Scholar] [CrossRef] [Green Version]
  82. Zhou, Y.; Zheng, X.; Chen, R.; Xiong, H.; Guo, S. Image-Based Localization Aided Indoor Pedestrian Trajectory Estimation Using Smartphones. Sensors 2018, 18, 258. [Google Scholar] [CrossRef] [Green Version]
  83. Al-Madani, B.; Orujov, F.; Maskeliunas, R.; Damasevicius, R.; Venčkauskas, A. Fuzzy Logic Type-2 Based Wireless Indoor Localization System for Navigation of Visually Impaired People in Buildings. Sensors 2019, 19, 2114. [Google Scholar] [CrossRef] [Green Version]
  84. Wang, Y.; Hussain, A.; Soltani, M. A MEMS-based adaptive AHRS for marine satellite tracking antenna. IFAC-PapersOnLine 2015, 48, 121–126. [Google Scholar] [CrossRef] [Green Version]
  85. Wan, E.A.; Van Der Merwe, R. The unscented Kalman filter for nonlinear estimation. In Proceedings of the IEEE 2000 Adaptive Systems for Signal Processing, Communications, and Control Symposium (Cat. No. 00EX373), Lake Louise, AB, Canada, 4 October 2000; pp. 153–158. [Google Scholar]
  86. Julier, S.J.; Uhlmann, J.K. Unscented filtering and nonlinear estimation. Proc. IEEE 2004, 92, 401–422. [Google Scholar] [CrossRef] [Green Version]
  87. Ghobadi, M.; Singla, P.; Esfahani, E.T. Robust attitude estimation from uncertain observations of inertial sensors using covariance inflated multiplicative extended Kalman filter. IEEE Trans. Instrum. Meas. 2017, 67, 209–217. [Google Scholar] [CrossRef]
  88. Eckert-Gallup, A.; Martin, N. Kernel density estimation (KDE) with adaptive bandwidth selection for environmental contours of extreme sea states. In Proceedings of the OCEANS 2016 MTS/IEEE Monterey, Monterey, CA, USA, 19–23 September 2016; pp. 1–5. [Google Scholar]
  89. Rabiner, L.; Juang, B. An introduction to hidden Markov models. IEEE ASSP Mag. 1986, 3, 4–16. [Google Scholar] [CrossRef]
  90. Oudelha, M.; Ainon, R.N. HMM parameters estimation using hybrid Baum-Welch genetic algorithm. In Proceedings of the 2010 International Symposium on Information Technology, Kuala Lumpur, Malaysia, 15–17 June 2010; Volume 2, pp. 542–545. [Google Scholar]
  91. Yen, Y.; Fanty, M.; Cole, R. Speech recognition using neural networks with forward-backward probability generated targets. In Proceedings of the 1997 IEEE International Conference on Acoustics, Speech, and Signal Processing, Munich, Germany, 21–24 April 1997; Volume 4, pp. 3241–3244. [Google Scholar]
  92. Yang, W.; Xiu, C.; Zhang, J.; Yang, D. A novel 3D pedestrian navigation method for a multiple sensors-based foot-mounted inertial system. Sensors 2017, 17, 2695. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  93. Brena, R.F.; García-Vázquez, J.P.; Galván-Tejada, C.E.; Muñoz-Rodriguez, D.; Vargas-Rosales, C.; Fangmeyer, J. Evolution of indoor positioning technologies: A survey. J. Sens. 2017, 2017. [Google Scholar] [CrossRef]
  94. Friis, H.T. A note on a simple transmission formula. Proc. IRE 1946, 34, 254–256. [Google Scholar] [CrossRef]
Figure 1. Hybrid position error compensation mechanism For indoor localization.
Figure 1. Hybrid position error compensation mechanism For indoor localization.
Sensors 21 06972 g001
Figure 2. Quaternions calculation at north–east down (NED) reference. (a) Quaternions calculation at inertial frame; (b) Quaternions calculation at new frame.
Figure 2. Quaternions calculation at north–east down (NED) reference. (a) Quaternions calculation at inertial frame; (b) Quaternions calculation at new frame.
Sensors 21 06972 g002
Figure 3. Orientation Estimation Based on UKF.
Figure 3. Orientation Estimation Based on UKF.
Sensors 21 06972 g003
Figure 4. Transitions Regions between all performed Activities.
Figure 4. Transitions Regions between all performed Activities.
Sensors 21 06972 g004
Figure 5. BLE-beacon Compensation Mechanism Based on Kalman Filter and AWCLA.
Figure 5. BLE-beacon Compensation Mechanism Based on Kalman Filter and AWCLA.
Sensors 21 06972 g005
Figure 6. Activity detection using measurements of accelerometer sensor data.
Figure 6. Activity detection using measurements of accelerometer sensor data.
Sensors 21 06972 g006
Figure 7. Clustering of IMU sensor data.
Figure 7. Clustering of IMU sensor data.
Sensors 21 06972 g007
Figure 8. Filtered RSSI values and raw RSSI values. (a) BLE-beacon RSSI values around Conference room; (b) BLE-beacon RSSI values around stairs area; (c) BLE-beacon RSSI values around MCL; (d) BLE-beacon values around elevator area.
Figure 8. Filtered RSSI values and raw RSSI values. (a) BLE-beacon RSSI values around Conference room; (b) BLE-beacon RSSI values around stairs area; (c) BLE-beacon RSSI values around MCL; (d) BLE-beacon values around elevator area.
Sensors 21 06972 g008
Figure 9. Position Calculation based on EPBCM, PDR, and BLE-beacon at different mobile locations.
Figure 9. Position Calculation based on EPBCM, PDR, and BLE-beacon at different mobile locations.
Sensors 21 06972 g009
Figure 10. Mobile position estimation using BLE-beacon, PDR, and the EPBCM algorithm.
Figure 10. Mobile position estimation using BLE-beacon, PDR, and the EPBCM algorithm.
Sensors 21 06972 g010
Figure 11. Indoor localization visualization using IMU sensor data.
Figure 11. Indoor localization visualization using IMU sensor data.
Sensors 21 06972 g011
Figure 12. Performance evaluation of the proposed localization model considering pedestrian walking trajectories. (a) Pedestrian walking experiment; (b) Person walking trajectory evaluation by using EPBCM and PDR based localization algorithms.
Figure 12. Performance evaluation of the proposed localization model considering pedestrian walking trajectories. (a) Pedestrian walking experiment; (b) Person walking trajectory evaluation by using EPBCM and PDR based localization algorithms.
Sensors 21 06972 g012aSensors 21 06972 g012b
Table 1. Critical analysis of existing technologies for positioning error in IPS.
Table 1. Critical analysis of existing technologies for positioning error in IPS.
SensorsTechniqueEnvironmentMax DistanceError in MetersAchieved
Accuracy
Gyro, Acc [73]Zero velocity update, map matchingSensor mounted on person′s waist40 m0.683 m98.26%
Mag, Acc [74]PDR, map matchingSensor in person′s pocket104 m(0.55–0.93) mAve LE,
(0.55–0.93) m
Acc, Gyro [75]Quaternion complementary filterSmartphone placed
in trousers, jacket, and held in hand
270 m0.529 mAbove 98%
IMU [76]Learning prediction system and
improving parameters of the alpha–beta filter
NGIMU sensor attached to person′s body∼50 m0.102 mAbove 98.7%
IMU [77]Learning module, based on ANN
and KF are used as the prediction algorithm
Prediction of actual sensor reading
from Noisy measurements
∼50 m0.009 mAbove 99%
Acc, Gyro [78]Model classificationMobile phone in person′s hand and pocket
while walking
168.55 m0.31 mAve LE, 1.35 m
Acc, Gyro, Wi-Fi [56]Zigbee RSSI fusion based on EKF with PDRZigbee and IMU sensor mounted on
person waist
25 mN/AMax LE, 4 m
Acc, Gyro, Mag, RFI [79]RFID RSSI fusion based on EKF with PDRIMU mounted on person′s foot and RFID
tags installed in rooms
1000 m0.721 mAve LE, 98.73%
Acc, Gyro [80]Assistive QR code with PDRscan QR code along the path and kept
smartphone in hand
35 mN/AAbove 99%
IMU, BLE beacon [81]BLE beacon, inertial dead reckoningindoor environment40 mN/AAbove 97.47%
IMU, camera [82]PDR, camerameeting room15 m0.56 mN/A
BLE-beacon [83]Fuzzy logic, BLE fingerprintingIndoor enviornment25 m0.43 mN/A
Table 2. Description of notations and symbols used in the formulation.
Table 2. Description of notations and symbols used in the formulation.
NotationDescription
{ i n f } Inertial navigational frame.
{ s b f } Sensor-body frame.
s R Scaler part of quaternions.
v ( x , y , z ) Vector part of quaternions, where v R 3 .
qUnit quaternion.
q Conjugate quaternion.
Multiplication operation
v i n f Vector in the inertial navigational frame.
v s b f Vector in the sensor body frame.
i , j , and kA quaternion basis elements.
α , β , γ and δ Quaternion real numbers.
q i n f s b f The unit-vector quaternion encoding rotation from the inertial navigational frame to the body frame of the sensor.
α The amount of rotation that should be performed about the vector part.
σ 1 , σ 2 , and  σ 3 Elements σ 1 , σ 2 , and  σ 3 thought of as a vector about which rotation should be performed.
ϕ The angle of rotation.
ϵ Unit vector representing the axis of rotation.
Q ( q ) Rotation matrix.
QFour-dimensional vector space over the real numbers R 4 .
N E D North–east down
ψ Rotation around yaw.
ξ Rotation around pitch.
φ Rotation around roll.
a t a n 2 Computes the principal value of the argument function applied to the complex number in the quaternion.
δ ϕ Prior gyros bias errors. The error between estimated gyroscope bias and true gyroscope bias.
δ ψ Euler angles errors.
xState vector of the proposed filter.
e q Error quaternions.
eAttitude error.
x ˙ k = A k x k + E u k The state equation for the attitude estimation system.
u k The noise vector, which refers to the noise related to the rotation error angle.
ζ δ Ψ ( t ) Noise error, true bias random walk.
ζ Δ Φ ( t ) Noise error, estimated bias random walk.
w ^ b / n b The estimated rotation rate.
a c c ˜ s b f Output of accelerometer.
m a g ˜ s b f Output of magnetometer.
yMeasurement of the combination of the accelerometer and magnetometer.
η acc s b f and η mag s b f The measurement independent zero-mean Gaussian white-noise.
m n and g n True magnetic and gravity vector.
η a c c s b f 2 and η m a g s b f 2 The variance of measurement noise.
M R Covariance matrix.
h ( q ) Represents the nonlinear equations that convert the magnetometer reference vector r m a g R 3 and accelerometer reference vector r a c c R 3 from INF to the SBF.
ρ Sigma points.
λ Represents the scaling parameter that shows the sigma points spread around the column vectors of the covariance matrix.
K x j prior The prior estimates of covariance.
ρ Posterior sigma points.
W i m and W i j Used to calculate the mean and covariance of the posterior sigma points.
μ Determines the spread of the ρ around x ^ k prior and β accentuate the weighting on the zeroth ρ .
( y ˜ ) Residual error.
D ( . ) Distribution constructed by the kernel density estimate.
wO,t (.)Weight assigned to each activity performed in the various dedicated zones Z i .
Table 3. Performed activities and range of accelerated values.
Table 3. Performed activities and range of accelerated values.
Performed
Activities
Working on
Computer
Running
Activity
Walking
Upstairs
Walking ActivityWriting on
White Board
Range of
Acc Values
α 1 α o α 2 α 2 α o α 3 α 3 α o α 4 α 4 α o α 5 α 5 α o α 6
Table 4. Implementation environment.
Table 4. Implementation environment.
ComponentDescription
BLE Beacon modelEstimote
CPU32-bit ARM® Cortex M0
Power sourceCR2477
Battery life3 years
Ideal beacons range70 m (230 feet)
Practical beacons range30–40 m
Radio frequency2.4 GHz UHF
VersionBluetooth 4.0 Smart
Sensors embeddedAccelerometer, temperature
Table 5. Implementation environment.
Table 5. Implementation environment.
ComponentDescription
Operating systemAndroid OS
HardwareBLE-beacon ARM® Cortex®-M4 32-bit processor with FPU, Smartphone, Intel(R) Core(TM) i5-8500 CPU @ 3.00GH
MemoryDDR4-16GB RAM, 64 kB RAM
LibrariesGoogle API, Android Graph Library, Android Position Library
Front end frameworkSwing based GUI
Core programming languageJava
IDEAndroid Studio
Simulation time60 s (1 min)
Table 6. Comparion in Position Error-Reference and EPBCM.
Table 6. Comparion in Position Error-Reference and EPBCM.
Reference Position X True
Meters
Y True
Meters
X EPBCM
Meters
Y EPBCM
Meters
Position Error
Elevator Area61.26.061.260.08
Conference Room31.93.111.890.11
Stairs Area102.410.322.360.32
Mobile Computing Lab111.011.0050.01
Networking Lab153.7415.653.660.65
Rest Area205.3220.115.40.14
Table 7. Comparison of reference position with EPBCM, PDR, and BLE-beacon-based localization algorithms.
Table 7. Comparison of reference position with EPBCM, PDR, and BLE-beacon-based localization algorithms.
Reference Position X True
Meters
Y True
Meters
X EPBCM
Meters
Y EPBCM
Meters
X BLE beacon
Meters
Y BLE beacon
Meters
X PDR
Meters
Y PDR
Meters
Elevator Area61.26.061.266.131.276.071.39
Conference Room31.93.111.893.081.983.12.04
Stairs Area102.410.322.3610.72.4711.32.54
Mobile Computing Lab111.011.0050.991.011.031.04
Networking Lab153.7415.653.6615.093.3316.23.64
Rest Area205.3220.115.421.45.5321.895.62
Publisher′s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Jamil, H.; Qayyum, F.; Jamil, F.; Kim, D.-H. Enhanced PDR-BLE Compensation Mechanism Based on HMM and AWCLA for Improving Indoor Localization. Sensors 2021, 21, 6972. https://doi.org/10.3390/s21216972

AMA Style

Jamil H, Qayyum F, Jamil F, Kim D-H. Enhanced PDR-BLE Compensation Mechanism Based on HMM and AWCLA for Improving Indoor Localization. Sensors. 2021; 21(21):6972. https://doi.org/10.3390/s21216972

Chicago/Turabian Style

Jamil, Harun, Faiza Qayyum, Faisal Jamil, and Do-Hyeun Kim. 2021. "Enhanced PDR-BLE Compensation Mechanism Based on HMM and AWCLA for Improving Indoor Localization" Sensors 21, no. 21: 6972. https://doi.org/10.3390/s21216972

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