Next Article in Journal
Development of Multilayer Transducer and Omnidirectional Reflection Model for Active Reflection Control
Previous Article in Journal
Privacy Preserving Image Encryption with Optimal Deep Transfer Learning Based Accident Severity Classification Model
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Precision-Driven Multi-Target Path Planning and Fine Position Error Estimation on a Dual-Movement-Mode Mobile Robot Using a Three-Parameter Error Model

1
Department of Mechanical Engineering, Tsinghua University, Beijing 100084, China
2
Moscow Engineering Physics Institute, National Research Nuclear University MEPhI, Moscow 115409, Russia
3
Blagonravov Mechanical Engineering Research Institute RAS, Malyi Kharitonievsky per.4, Moscow 101990, Russia
4
Department of Mechanical Engineering, Federal University of Santa Catarina, Florianópolis 88040-900, Brazil
*
Author to whom correspondence should be addressed.
Sensors 2023, 23(1), 517; https://doi.org/10.3390/s23010517
Submission received: 12 November 2022 / Revised: 10 December 2022 / Accepted: 29 December 2022 / Published: 3 January 2023
(This article belongs to the Section Electronic Sensors)

Abstract

:
The multi-target path planning problem is a universal problem to mobile robots and mobile manipulators. The two movement modes of forward movement and rotation are universally implemented in integrated, commercially accessible mobile platforms used in logistics robots, construction robots, etc. Localization error in multi-target path tracking is one of the crucial measures in mobile robot applications. In this article, a precision-driven multi-target path planning is first proposed. According to the path’s odometry error evaluation function, the precision-optimized path can be discovered. Then, a three-parameter odometry error model is proposed based on the dual movement mode. The error model describes localization errors in terms of the theoretical motion command values issued to the mobile robot, the forward moving distances, and the rotation angles. It appears that the three error parameters follow the normal distribution. The error model is finally validated using a mobile robot prototype. The error parameters can be identified by analyzing the actual moving trajectory of arbitrary movements. The experimental localization error is compared to the simulated localization error in order to validate the proposed error model and the precision-driven path planning method. The OptiTrack motion capture device was used to capture the prototype mobile robot’s pose and position data.

1. Introduction

The target sequencing problem is a typical planning problem. One of the most famous target sequencing problems is the traveling salesman problem (TSP). It has been a long time since the TSP was first proposed. It is a problem of how to arrange the shortest possible route which visits each city once. There are many variants: the colored traveling salesman problem [1], the intermittent traveling salesman problem [2], the traveling salesman problem with release times [3], the traveling salesman problem with draft limits [4], and large-scale general colored traveling salesman [5]. As robotic technology advances, a mobile robot faces multi-target path planning problems in numerous circumstances [6,7,8,9]. The usual optimization criteria of the planning algorithm are the path length or the time cost [10,11,12]. There are other kinds of criteria for the path. Gao et al. [13] proposed a localizability evaluation method to find the path with optimal localizability. Zhang et al. [14] proposed criteria for considering the path length and angle and applied the path planning method in the greenhouse. However, the weights of the path length and path angle in the evaluation function in [14] are equal, which leads to a less meaningful application in reality.
Localization is one of the major tasks of mobile robot navigation. Wheel odometry is a critical foundation for localization in the sequencing of moving tasks. In the absence of an absolute positioning system, the positional error of mobile robots is accumulated. As the accumulated localization errors are different between different pathed sequences, a theoretically precise optimal path exists for the multi-point path planning problem. The prerequisite for solving the precision-driven multi-point path planning problem is the accurate error model for the mobile robot in sequencing its movements. Some motion error models for the mobile robot have been built. The error model of the mobile robot predicts position error in multiple-target tracking. The UMBmark [15] is a widely used, typical scheme of odometry error estimation based on the differential drive. The calibration strategy in UMBmark supposes that the wheel radius error and the wheelbase error are independent. Lee et al. [16] proposed an updated calibration strategy over UMBmark, considering that these two elements are affected by coupling. The disturbances of applied forces on the wheels are considered to derive the error model [17,18]. Filho et al. [19] proposed an analysis method for the impact of parametric uncertainties, in other words the non-systematic error parameters, on the localization error. However, these odometry error models strongly correspond to the structure of the mobile robot, such as the wheel radii, the distance between the wheels, the center of mass, etc. Most calibration methods are restricted to the limited specific structure of mobile robots.
Along with the development of robot technology, the complex integrated robot, for instance, the mobile manipulator, uses the integrated and commercial mobile base, such as the Segway RMP 440 Omni Flex [20], the HUSKY mobile platforms [21], etc. When facing a specific application for the mobile manipulator, the main program is usually considered the element motion with only two modes, moving forward and rotating in situ [22,23]. The requirement of the developers is the calibration functions on the moving distances and rotating angles in command without a detailed analysis of the structure’s properties of the mobile base. The odometry calibration strategy, which is responsible for the input commands to the mobile base, is required.
Based on the above analysis, this paper makes three major contributions to the current state of research.
First, a method for precision-driven multi-target path planning is proposed. The routing sequence of the known target positions expresses the resultant path. The evaluation function represents the localization precision of the path. In this study, the target positions are fixed and known. The precision-driven multi-target path planning problem in this study is also a target sequencing problem. As the genetic algorithm (GA) is valid for solving the traveling salesman problem [24,25] and target sequencing problems [26,27], the GA is used to find the optimal routing sequencing in this section.
Second, a three-parameter error model based on the dual-mode moving mobile robot is then proposed. The localization error of the path is expressed as a function of the input moving distances and the rotating angles. The proposed error model suits any mobile robot whose motion types are only moving forward and rotating in situ. The three parameters are the forward moving error coefficient, k s , the rotation angle error coefficient, k r , and the rotation center lateral offset, d r . The properties and the rationalities of the proposed parameters are discussed in this article. Moreover, the compensation equations for the movement commands are proposed to increase the odometry precision based on the known error parameters.
Third, the error parameter identification method based on the random movements of the mobile robot is proposed. The error parameters are seen to follow the normal distribution. By collecting the moving trajectory of random movements and the corresponding moving commands of moving forward and rotating, the distribution of the model parameters can be calculated.
In this study, a prototype of a mobile robot was built to validate the formerly proposed contributions. Only the forward movement and rotation of the mobile robot are used to reach the target points. The motion capture system OptiTrack is commonly used to record dynamic motions [28,29]. The motion capture system records the detailed motion of all movements. To validate the proposed error model, comparisons were made between the simulated positions and the experimental positions in multiple-target tracking. Comparisons of both before and after motion calibration were made.
This paper is organized as follows. Section 2 proposes the formulation of the precision-driven multi-target path planning problem. The detail of the three parameters’ model is provided in Section 3. The parameters’ identification on the prototype mobile robot is shown in Section 4. The comparisons of the simulated stop positions and the experimental stop positions are reported in Section 5. The compensation methods based on the known error parameters to obtain a higher precision movement are introduced in Section 6. The discussion and conclusions are separately presented in Section 7 and Section 8.

2. Generalized Multiple-Target Path Planning Problem

Suppose there is a workspace with the length of l and the width of w . There are n target positions scattered in this workspace. The target for the mobile robot is to move to each target point with the lowest costs. In Figure 1, the points in black denote the target positions. The path planning algorithms find the optimal path which connects each target position.
The set of target points can be expressed by
G = { g 1 , · · · , g n } , g i C
Each element g i represents one target position, and the number of the element in the set G is n , which denotes the number of target positions in the workspace.
As shown in Figure 1, a coordinate system is built on the ground of the workspace.
The motion modes for the robot in this article are forward movement and rotation in situ. The method of ideal rotation is to rotate across the center point of the mobile robot. Rotating around its center is a common ability for a mobile robot. As the example shows in Figure 2, a four-wheel robot has the capability of moving forward and rotating in situ. The arrows in black represent the motion direction of each wheel, and the arrows in blue represent the rotating direction around the center of the robot.
Figure 2a shows the mode of forward movement, and Figure 2b shows the mode of rotation in situ. In this situation, the total movements of the mobile robot moving along a multiple target points path can be composed of these two modes. The four-wheel structure shown in Figure 2 is just an example. The number of wheels can be two, three, or four. Even a mobile robot with crawlers suits the method proposed in this article.
Suppose that the initial position of the mobile robot is P i ; the next position the mobile robot moves to is P i + 1 . The mobile robot first rotates in situ, and the forward direction of the mobile robot is adjusted towards the next position. Then, the mobile robot moves in the forward direction until reaching the target’s next position.
The quantitative values of these two motions are defined by the forward moving distances and turning angles moving from one target point to the next. However, the movement’s actual quantitative value is not the same as the expected quantitative value because of the movement error.
Because of this movement error, the actual positions are P i * , corresponding to the ideal positions, P i . The subscript i denotes the indexes for the position. Thus, the average location error for the entire multi-target points path can be expressed.
X = i = 1 n d ( P i , P i * ) n
The symbol X represents the average location error. The operator d ( P i , P i * ) represents the distance between the ideal position P i to the actual position P i * .
The motion error causes the position error at each movement, and the movements are classified into two modes, forward movement and rotation. Suppose that the moving distances of each forward movement is l i , and the turning angle of each turning in situ is θ i . The motions can also express the average position error.
X = f ( L * , θ * )
Equation (3) represents the generalized evaluation function. The symbol L * in Equation (3) represents the actual distances array of moving forward.
L * = ( l 1 * , l 2 * , , l n * )
where the elements are the true distances, l i * , corresponding to the ideal distances, l i .
The symbol θ * represents the actual angles array of turning in situ.
θ * = ( θ 1 * , θ 2 * , , θ n * )
where the elements are the true angles, θ i * , corresponding to the ideal angles, θ i .
The true motion vector, ( θ i * , l i * ) , can be seen as the function of the ideal motion pair, ( θ i , l i ) .
[ θ i * , l i * ] = Ε ( θ i , l i )
The structure of the function, Ε ( θ i , l i ) , is defined as the error function of the mobile robots. The error model is affected by the inner properties of the mobile robots.
According to Equations (3) and (5), as long as the structure of the evaluation function f ( L * , θ * ) and Ε ( θ i , l i ) are determined, the average position error can be seen as the optimization criterion to calculate the optimal multiple-target path.
The typical shortest total length path problem is a special status of Equation (3), as shown in Equation (7).
X l = f ( L * , θ * ) = i = 1 n l i n
In Equation (7), the structure of the evaluation function is simplified to the summation of the distances between the adjacent target positions on the path.
Suppose that there are 20 target points placed in the square workspace. The coordinates of the target positions are shown in Table A1. The length of the workspace is 1000 mm, and the width of the workspace is 1000 mm, as shown in Figure 3a. The start point of the path is set as the top left point of the workspace, ( 0 , 1000 ) , and the end point of the path is set as the bottom right point of the workspace, ( 1000 , 0 ) .
The pattern in Figure 3b shows the shortest path result for the multi-target path planning problem.
What is more, when the summation of the rotation angle defines the evaluation function, the evaluation is shown in Equation (6).
X l = f ( L * , θ * ) = i = 1 n θ i n
Corresponding to the least summation of the turning angle, the optimal path is shown in Figure 3c.
In Figure 3, the dots in black represent the target points. The lines in red represent the moving paths for mobile robot. As the quantitative value of two characteristic movement modes are the moving distance and the rotating angle, the path shown in Figure 3a,b constitute the two characteristic paths. To recall these two characteristic paths simply, they are called the path with the shortest length and the path with the least rotation in the rest of this article.

3. Three Parameters’ Error Model for Mobile Robots

When the mobile robot executes the multiple-target path, the position the robot reaches is not the precise position of the target. Figure 4 shows realistic example experiment data for a mobile robot moving along the path with the shortest length.
Figure 4a shows the actual positions and the ideal positions. The points in red denote the ideal positions. In Figure 4a, the points and lines in blue denote the actual positions and moving paths captured by the motion capture system. Figure 4b shows the error polyline of the total movements. The error is defined as the distance between the actual and ideal positions.
The proposed error model is composed of three parameters, the forward moving error coefficient, k s , the rotation angle error coefficient, k r , and the rotation center lateral offset, d r . In this part, the three parameters are explained in detail. Then, the position estimation equations of the multiple-target path are proposed.

3.1. Forward Moving Error Coefficient

Suppose that the expected moving distance is l , and the true moving distance is l * . The proposed error model considers that the numerical relationship between the expected moving distance and the true moving distance is
l * = k s l
In Equation (9), the coefficient of the expected moving distance, k s , denotes the forward moving error coefficient, which is one of the three error parameters of the error model proposed in this article.
The forward moving error coefficient, k s , can be seen as the comprehensive influence of the changing wheel radius and the changing tire slip.
The encoder, combined with the wheel’s axis, constitutes the feedback of the movement control. The controlled function of the wheel can be expressed by
N = N 0 l 2 π r
In Equation (10), N denotes the pulse change in the wheel encoder, N 0 denotes the number of pulses per revolution of the encoder, r represents the radius of the wheel, and l denotes the moving distance to be controlled.
l * = 2 π r k s N N 0
Substituting Equation (9) into Equation (10), Equation (11) expresses the true control function for one wheel movement.
The forward moving distance error can be affected by the deformation of the transmission system, the deformation of the wheel, the tire slip, etc. These error factors can be summarized by the forward moving error coefficient, k s .

3.2. Rotation Angle Error Coefficient

Suppose that the expected rotation angle is θ , and the true turning angle is θ * . The proposed error model considers that the numerical relationship between the expected rotation angle and the true turning angle is
θ * = k r θ
In Equation (12), the coefficient of the expected turning angle, k r , denotes the rotation angle error coefficient, which is one of the three error parameters of the error model proposed in this article.
The error in the rotation angle is also affected by the non-ideality of the mobile robot. Moreover, the contact situation on the tire between moving forward and turning is different. These two coefficients are seen as orthogonal.

3.3. Rotation Center Lateral Offset

Either in the forward moving error coefficient or the turning angle error coefficient, the moving speed of the wheel at each side of the mobile robot is considered the same. The difference in speed between the two sides of the mobile robot causes the rotation center lateral offset, d r .
Because the speed of each side of the mobile robot is different, when the mobile robot rotates in situ, the true rotation center of the mobile robot shifts from the geometric center.
The rotation center lateral offset, d r , is defined as the center offset projection on the direction which is normal to the forward direction of the mobile robot. Moreover, the center offset is defined as the segment which connects the true center and the geometric center.
Suppose there is an observer who stands at the geometric center of the mobile robot, and his/her forward direction is coincident with the forward direction of the mobile robot. If the true center is at the right of the observer, the numerical value of the rotation center lateral offset, d r , is defined as positive. Similarly, if the true center is at the left of the observer, the numerical value of the rotation center lateral offset, d r , is defined as negative.
The rotation center lateral offset reflects the wheel movement difference on two sides. No matter what the structure of the mobile robot is, two wheels, four wheels or other, the mobile robot can be seen as a symmetrical model. Figure 4 shows the geometrical relationship between the wheel movement difference and the rotation center lateral offset.
As shown in Figure 5, the mobile robot is equivalently substituted by the two-wheel model. The left wheel moves backward with the velocity v 1 . The right wheel moves forward with the velocity v 2 . If v 1 = v 2 , the mobile robot rotates around the geometrical center. If v 1 v 2 , the mobile robot rotates around the true center point, from which the distance to the geometrical center is d r , which is shown in red in Figure 5. The arrow in red represents the rotation direction.
As the distances of the two wheels to the true center differ, the two wheels move along circularly with different radii. Suppose that the spacing between the wheels on two sides is w , then the radius of the left wheel trajectory is w / 2 + d r , and the radius of the right wheel trajectory is w / 2 d r . The angular velocities of the two wheels are the same.
v 1 w / 2 + d r = v 2 w / 2 d r
Thus, the linear velocity ratio, k w , of wheels on two sides is
k w = v 1 v 2 = w + 2 d r w 2 d r
The offset of the rotation center affects the shape of the forward-moving trajectory. Because of the linear velocity difference between the two sides, the trajectory of moving forward performs like an arc, as shown in Figure 5.
Figure 6 shows the true trajectory of moving forward. Suppose that the linear velocity of the left wheel is v 1 , and the linear velocity of the right wheel is v 2 . If v 1 = v 2 , the trajectory of moving forward is straight. If v 1 v 2 , the trajectory of moving forward performs like an arc.
Suppose that the trajectory radius of the left wheel is R 1 , and the trajectory radius of the right wheel is R 2 . The linear velocity ratio between two wheels is also
v 1 v 2 = ω R 1 ω R 2 = w + 2 d r w 2 d r
The angular velocities are the same at each point of the trajectory, and the trajectory radius of the true center of the mobile robot R s can be expressed by
R s = R 1 w 2 = R 2 + w 2
Substitute Equation (16) into Equation (15):
R s = w 2 4 d r
As the rotation center lateral offset, d r , can be negative, the generalized trajectory radius of the true center can be negative in this situation.
According to Figure 5 and Figure 6, the trajectory caused by the offset of the rotation center and the non-linear trajectory of moving forward is the wheel linear velocity difference between the left and right equivalent wheels. Different factors lead to different slip rates between the tire and the ground.
Since the left and right sides of the general mobile robot often use the same type of motors and tires, the actual value of rotation center lateral offset is very small, far less than the left and right wheel spacing, so the impact on the rotation movement precision is also small.
Moreover, what the rotation center lateral offset, d r , really affects is the trajectory shape of moving forward. The ideal straight motion of moving forward changes to the circular motion described by Equation (13). However, we define this effect as the rotation center lateral offset rather than the trajectory radius of moving forward because the true rotation center, compared with the circle center of the forward-moving trajectory, is on the mobile robot, not outside the mobile robot. Moreover, the rotation center lateral offset can be negative, corresponding to the circle center on the left.
The rotation center lateral offset parameter is used to explain the non-ideal property of moving forward, that is, the radius of the forward-moving trajectory R s . Hence, only the nominal value of the wheel spacing, w , which is used in Equation (13), is needed.
The linear velocity difference between the wheels on both sides will affect the former two error parameters, k s and k r , but this effect is so small that it can be ignored. This discussion will be presented in Section 4 with experimental data.

3.4. Error Evaluation Function in Multi-Target Path Moving

When the mobile robot moves along the multi-target path, the error at each position is related to each previous step. According to the known details of the error model at each step, the error performance of each point in the multi-target path can be estimated. At the same time, according to the error performance of each step, the motion path with the smallest error can be solved for the multi-objective path planning problem.
Firstly, the situation of a mobile robot moving between two points is discussed with the proposed three error parameters.
When the mobile robot executes the motion from the initial point, P ( x P , y P ) , to the target point, Q ( x Q , y Q ) , the mobile robot moves from the initial true point, P ( x P , y P ) , to the true target point, Q ( x Q , y Q ) . When the actual positions of the mobile robot are P ( x P , y P ) and Q ( x Q , y Q ) , the robot thinks it is at positions P ( x P , y P ) and Q ( x Q , y Q ) .
The true target position, Q ( x Q , y Q ) , can be expressed by
[ x Q y Q ] = [ x P y P ] + [ cos ( 2 d r k s d P Q w 2 ) sin ( 2 d r k s d P Q w 2 ) sin ( 2 d r k s d P Q w 2 ) cos ( 2 d r k s d P Q w 2 ) ] [ k s ( x Q x P ) k s ( y Q y P ) ]
In Equation (18), d P Q denotes the distance from point P to Q , k s denotes the forward moving error coefficient, d r denotes the rotation center lateral offset, and w denotes the nominal spacing between the wheels on both sides. The moving error between two points is independent of the turning angle error coefficient.
If the motion from point P ( x P , y P ) to point Q ( x Q , y Q ) is considered ideal, then the final pose vector after the movement is
p Q = [ x Q x P y Q y P ]
However, the movement is non-ideal. The true pose vector is
p Q = [ x Q x Q + 2 x P x P 2 y Q y Q + 2 y P y P 2 ]
Equation (20) is an approximate equation. The approximate condition is
| R s | = | w 2 / 4 d r | d P Q
If the approximate condition is invalid, the true pose vector is
p Q = [ x Q x P R s ( x Q x P d P Q ) tan ( d P Q 2 R s ) y Q y P R s ( y Q y P d P Q ) tan ( d P Q 2 R s ) ]
The movement error is irrelevant to the turning angle error coefficient in this situation.
Next, the error performance of continuous movements between multiple points is discussed.
The movement discussed in Equation (14) supposes that the initial pose is from the ideal initial point P to the ideal target point Q . That is,
p 0 = p Q = [ x Q x P y Q y P ]
However, before the mobile robot executes the movement from the ideal initial point P to the ideal target point Q , the ideal initial pose p P is dependent on the former movement before reaching point P . The initial true pose at point P is p P , which is dependent on every former movement.
Hence, the actual movements between the true point P ( x P , y P ) and the true point Q ( x Q , y Q ) can be expressed as below. Firstly, the mobile robot turns in situ. The forward direction is adjusted to the next target point. Then, the mobile robot moves forward straightly to the next target point. The turning angle error coefficient affects the actual turning angle in the rotation movement. The movements are shown in Figure 6.
As shown in Figure 7, when the mobile robot finishes the movement from point O to point P , the ideal position is P ( x P , y P ) , and the true position is P ( x P , y P ) . The ideal pose vector is p P = ( x P x O , y P y O ) T . The true initial pose vector is p P = ( x P x O , y P y O ) T .
In Figure 7, the straight arrows in red represent the forward direction when the robot reach the points P and P . And the curved arrows in red represent the rotation movements before moving to the points Q and Q . Before the mobile robot moves from point P to point Q , the mobile robot turns in situ. The ideal turning angle θ P is
θ P = arccos p P · p Q p P 2 p Q 2
Because of the turning angle error coefficient, k r , the true turning angle is
θ P = k r θ P
Hence, the value difference between the ideal turning angle and the true turning angle is
θ P θ P = ( k r 1 ) θ P
Then, the revised equation for Equation (18) is
[ x Q y Q ] = [ x P y P ] + [ cos ( β ) sin ( β ) sin ( β ) cos ( β ) ] [ k s ( x Q x P ) k s ( y Q y P ) ]
In Equation (27), β represents the equivalent turning angle:
β = 2 d r k s d P Q w 2 + ( k r 1 ) θ P
According to Equation (22), when considering the turning angle error, the final pose after reaching the target point, p Q , is
p Q = [ x Q R s ( x Q x P l P Q ) tan ( d P Q 2 R s ) y Q R s ( y Q y P d P Q ) tan ( d P Q 2 R s ) ] [ cos ( k r θ P ) sin ( k r θ P ) sin ( k r θ P ) cos ( k r θ P ) ] p P
If the approximate condition (21) is valid, then the approximate equation of Equation (29) is
p Q = [ x Q x Q x P 2 y Q y Q y P 2 ] [ cos ( k r θ P ) sin ( k r θ P ) sin ( k r θ P ) cos ( k r θ P ) ] p P
For the multi-target path planning problem, the set of target points is known. Using the coordinate point iteration Equation (27) and the pose vector iteration Equation (29), the actual positions from the start to the end can be estimated. The position error of any path can be estimated.

4. Error Parameters’ Estimation on Prototype Experiment

A mobile robot prototype was built, and the motion capture system was used to capture the movement of the mobile robot. The numerical value of the error parameters was estimated from the prototype experiment.

4.1. Error Evaluation Function in Multi-Target Path Moving

The prototype was composed of the chassis with four Mecanum wheels, as shown in Figure 8a,b. The Mecanum wheels were arranged symmetrically to implement the function of moving forward and rotating in situ. Figure 8b shows the overall view of the mobile robot.
The motion capture system uses the principle of a multi-view stereo vision system to calculate the 3-D coordinates of the marked points. Four motion capture cameras (Prime 17W, OptiTrack) were arranged to capture the sequenced coordinates of the marked points.
Three marked points were fixed to the top of the mobile robot, as shown in red in Figure 8c. The three points were arranged at the same height. The motion of the triangle center, C , represents the motion of the mobile robot, as shown in Figure 8d. The mobile robot moved on the ground. The coordinates of point C projected on the ground represent the coordinates of the mobile robot. The pose of the triangle, P 1 P 2 P 3 , represents the pose of the mobile robot.
The multiple-camera stereo system of OptiTrack is shown in Figure 8e. A marked point was observed by multiple cameras. The hollow circles in red represents the images of the marked points on the image coordinate system of each camera. The solid circle in red represents the calculated 3-D coordinates of the marked points according to the geometric relationship between cameras. The precision of the captured data depended on the number of cameras and the arranged geometry relationships. The error in the captured coordinates was smaller than 1 mm.

4.2. High-Precision Motion Recognition with Motion Capture System

The problem for motion recognition from time series data generated by the motion capture system is distinguishing between the motion and stationary segments. The vibration and disturbance of marked points constitute the noise in recorded 3-D coordinate data. According to the proposed three-parameter error model, the forward moving error coefficient, k s , corresponds to the distance difference between the expected moving distance and the actual moving distance. The turning angle error coefficient, k r , corresponds to the difference between the expected rotating angle and the actual rotating angle. The rotation center lateral offset, d r , corresponds to the shape of a forward-moving trajectory.
The actual moving distance and actual rotating angle, which correspond to the parameters k s and k r , are calculated from the stationary status of the mobile robot before and after movement. The arc-shaped trajectory is fit from the forward moving point series. Thus, a precise algorithm to distinguish between the stationary and motion segments is required to recognize the error parameters. Figure 9 shows the principle diagram of the proposed algorithm.
As shown in Figure 9a, the data generated from the motion capture system comprise a time coordinate series of a specific marked point. The coordinates series just before the point to be distinguished is called the left neighborhood. The coordinates series just after the point to be distinguished is called the right neighborhood. The left neighborhood positions are marked in different reds. The right neighborhood positions are marked in different blues.
Figure 9b shows an example of the stationary segment. The dotted unfilled circles in red and blue represent the average coordinates of the left and right neighborhoods. If the middle point to be judged is stationary, the coordinates of the left and right neighborhoods should be close.
Figure 9c shows the motion status. The distance between the two average coordinates is significant. If the middle point to be judged is motion, the average coordinates of the left neighborhood and the average coordinates of the right neighborhood are far from each other. The velocity of the middle point affects the numerical value of the distance.
Suppose that the point coordinates at the time t to be distinguished are
p t = ( x t , y t , z t ) T
The left neighborhood matrix, S t , l , can be expressed as
S t , l = [ p t m p t 1 ]
The right neighborhood matrix, S t , r , can be expressed as
S t , r = [ p t + 1 p t + m ]
where the integer m denotes the length of the neighborhood.
The coordinates of a specific point can be seen as a vector with three elements. A difference vector between two neighborhoods is defined to standardize the distinguishing criterion.
The difference vector of the neighborhood, s ˜ t , is defined as
s ˜ t = ( D ( p t m , p t + 1 ) , , D ( p t 1 , p t + m ) ) = ( d 1 , , d m )
where the operator D ( p i , p j ) represents the function of calculating the distance between point p i and point p j . The element d i represents the distances of the points from the point of the left neighborhood to the corresponding point of the right neighborhood.
The average difference, d ¯ , is defined as
d ¯ = i = 1 m d i m
The variance of differences, σ d 2 , is defined as
σ d 2 = i = 1 m ( d i d ¯ ) 2 m 1
Only when the average difference d ¯ and variance of differences, σ d 2 , are smaller than a specific threshold, d max and σ max 2 , can the middle point to be distinguished be called a stationary point. The value of the threshold depends on the noisy degree of the motion capture system.
Figure 9d,e show the status when the middle point is going to stop and going to start moving. The distance between two average coordinates is smaller. However, the variance of differences is larger compared with the pattern shown in Figure 9c.
Figure 10 shows an example of the stationary segmentation of continuous coordinate data captured by the motion capture system.
As shown in Figure 10, to express the difference between the motive segment and the stationary segment better, the captured data are shown with the velocity sequences. The velocity at a specific time is defined as the quotient of the distance between adjacent points by the time change in these two captured points. The motion segment is shown in red and the stationary segment is shown in blue.
Using the proposed stationary segment distinguishing algorithm, the entire motion capture coordinate series can be processed to the motion series, composed of the distances of moving forward and angles of rotating in situ.

4.3. Parameter Recognition Based on Arbitrary Mobile Robot Motions

To better recognize the error parameters, the movement should simulate the multi-target moving scenarios. Repeating the motion of moving forward or rotating in situ to generate the true data of the motion does not reflect the real situation.
Four random paths for the point pattern of Figure 3a were generated to act as the motion dataset, as shown in Figure A1.
Every expected value of movement and the true value of movement were calculated to fit the value of the error parameters.
An arc-shaped forward-moving trajectory segment is shown in Figure 11; the trajectory shape of the forward movement is obviously arc-shaped. The line in blue represents the initial data of the motion capturing. The line in red represents the center trajectory after the filter. The line in orange represents the fitted arc segment.
According to the forward-moving trajectory shown in Figure 11, the value of the rotation center lateral offset is positive.
By extracting every segment of the forward movement, the rotation center lateral offset can be recognized. The original data of the expected forward moving distance and actual forward moving distance are shown in Table A2. Moreover, the original data of expected and actual rotation angles are shown in Table A3.
Firstly, the forward moving error coefficient was fit with the ratio of the true distance and the expected moving distances, as shown in Figure 12a. In the three subfigures of Figure 12, the columns in blue represent the frequency at each value interval. The curve in red represents the fitted normal distribution function curve.
Secondly, the turning angle error coefficient was fit with the ratio of the true angles and the expected angles, as shown in Figure 12b.
The trajectory for forward-moving trajectory is arc-shaped. The radius of the trajectories was fitted for the error parameter recognition. Finally, the rotation center lateral offset fits with the arc fitting of the forward-moving trajectory, as shown in Figure 12c.
The result of the distribution fitting shows a normal distribution. The parameters of the normal distributions are shown in Table 1. The rotation center lateral offset, d r is calculated according to Equation (17), where the wheel track is w = 120   mm .
As shown in Table 1, the true rotation angle is usually larger than the expected rotation angle. In contrast, the actual forward moving distance is usually smaller than the expected forward moving distance.
The variance in k r is much larger than the variance in k s . After the error parameters are known, the experiment validates the error model. The error model was made to forecast the distribution of the multi-target moving error for a mobile robot.

4.4. Rationality Discussion of Error Parameters

According to the fitted data shown in Table 1, the rationality of the proposed three error parameters model can be proved. Substitute the fitted trajectory radius R into Equation (17). The rotation center lateral offset, d r , is negative. Hence, when the mobile robot prototype moves forward, the actual target position is always located at the ideal destination’s right, as shown in Figure 13.
Suppose that the ideal forward moving distance for the mobile robot is l . Because of the error parameter, d r , the actual shape of the trajectory is an arc. The radius of the trajectory is R s , and the arc length is also l . The ideal destination is point A , and the actual position after moving is point A . The arrow in red represents the forward direction of the mobile robot when it reach the point A . The starting point is O . The central angle of this circular movement is
α = l R s
The corresponding chord length of the trajectory is
d O A = 2 R s sin α 2
Substituting Equation (37) into Equation (38), the ratio of the chord length to the arc length is
d O A l = 2 R s l sin l 2 R s
Substituting the value of the error parameters and ideal length, l = 1000   mm , into Equation (39), the value of the ratio is d O A / l = 0.999928 . Moreover, the difference between the chord length and the arc length is d O A l = 0.072   mm . However, according to the value of the forward moving error coefficient, the actual forward moving error is about 25 mm. The error caused by the error parameter, k s , is much larger than the error caused by the error parameter, d r . If the trajectory radius is much larger than the moving distance, R l , the trajectory displacement can be seen as equal to the trajectory length, d O A l . Therefore, the forward moving error coefficient, k s , can be seen as orthogonal to the rotation center lateral offset, d r .
However, the distance between the expected and actual target positions cannot be ignored. The triangle A O A can be seen as an isosceles triangle. The vertex angle, β , of this isosceles triangle is
β = α 2
where α denotes the central angle shown in Equation (37). The distance between the target position and the actual ending position, Δ d , can be expressed as
Δ d = 2 l sin β 2
Substitute Equations (37) and (40) into Equation (41):
Δ d = 2 l sin l 4 R s
Then, substitute the prototype parameters and the ideal forward moving distance l = 1000   m into Equation (42): Δ d = 20.78   mm . This distance error is significant enough.
Not only is the error of the destination offset significant, the error between the ideal posture and the actual posture is also significant.
As shown in Figure 14, suppose that the starting direction vector is p s t a r t = O A , and the ending direction vector is p e n d = B A . The starting coordinate is O ( x O , y O ) , and the ideal destination coordinate is A ( x A , y A ) . The actual ending position coordinate is A ( x A , y A ) .
According to the discussed geometrical relationship shown in Figure 14, the movement from point O ( x O , y O ) to point A ( x A , y A ) can be expressed by a displacement and a rotation. The coordinate transformation equation shown in Equation (43) expresses the movement from point O ( x O , y O ) to point A ( x A , y A ) .
[ x A y A ] = [ x O y O ] + [ cos ( β ) sin ( β ) sin ( β ) cos ( β ) ] [ x A x O y A y O ]
where β represents the vertex angle of the isosceles triangle shown in Equation (40). Substitute Equations (17) and (37) into Equation (40):
β = 2 d r l w 2
According to the geometrical properties of the circular motion, the coordinates of point B ( x B , y B ) are
[ x B y B ] = [ x O + R s ( x A x O l ) tan ( l 2 R s ) y O + R s ( y A y O l ) tan ( l 2 R s ) ]
Thus, the ending direction vector p e n d can be expressed as
p = [ x A x B y A y B ] = [ x A x O R s ( x A x O l ) tan ( l 2 R s ) y A y O R s ( y A y O l ) tan ( l 2 R s ) ]
If the approximate condition, R s = | w 2 / 4 d r | l , is valid, Equation (46) can be approximated as
p = [ x A x A + x O 2 y A y A + y O 2 ]
That is, if the radius of the trajectory is much larger than the moving distance, R l , point B ( x B , y B ) can be approximated as the midpoint of the ideal movement segment O A .
Substituting the prototype parameters and the ideal forward moving distance l = 1000   mm into Equation (46), the included angle between the ideal ending direction vector O A and the actual ending direction vector B A is 0.0416 rad (2.381°).

5. Estimation of Error Distribution on Multi-Point Path Motion

According to Equation (3), as the parameters of the error model are found, shown in Table 1, the optimal route with the least error can be calculated. In this section, the theoretical precision optimal path is first proposed.
However, the error parameter is variable. A simulation with individual variable error parameters was made to determine the relationship between the parameter changing and the error changing.
Based on the variant parameters’ simulation, as the rotation error affects the average error the most, the path with the smallest summation angle has the least error. A prototype experiment validates the model.

5.1. Precision Optimal Path with Invariant Measured Error Parameters

Substitute the recognized error parameters shown in Table 1. The precision optimal path can be calculated by the genetic algorithm. The precision-driven optimal path is shown in Figure 14a. The theoretical position error comparison with three characteristic paths is shown in Figure 14b.
As shown in Figure 14a, the points in red represent the ideal target positions, and the points and path in blue represent the simulated motion path with recognized error parameters shown in Table 1.
Figure 14b shows the error comparisons among the three characteristic paths. The abscissa axis denotes the sequence of target points, and the ordinate axis denotes the position error at each target point.
The theoretical average error for the optimal precision path is 32.2795 mm. However, compared with the other paths, the average error of the shortest-length path is 46.3663 mm, and the average error of the least rotation path is 42.3186 mm. The precision optical path performs better than the other paths. What is more, the proposed precision optimal path has the best precision among all paths with any sequence of target points according to the calculated processing of the genetic algorithm.

5.2. Simulation with Variant Error Parameters

However, the error parameters are not constant at different movements. Along with the random change in the error parameters, the motion performances vary after every movement. Each parameter is considered to fit the normal distribution. The true position at every target point must fit a specific distribution. A simulation was made to show this distribution.
In the numerical simulations, each error parameter can be set as a random variable or a constant. When considering any error parameter as a constant, its value follows the value shown in Table 1. When considering any error parameter as a random variable, it fits a normal distribution with the same mean value shown in Table 1, and the same standard deviation shown in Table 1. Moreover, each simulation is made with different paths. The two characteristic paths are the minimum forward moving distance path and the minimum rotation angle path. Besides these two paths, the optimal precision path is simulated to show its superiority in precision. The results of the simulations are shown in Figure 15.
In each subfigure of Figure 15, the biggest points in red represent the ideal positions. The medium-size points in black represent the theoretical position when considering the error parameters as constant. The smallest points in blue represent the possible positions when considering the error parameters as the random variables. When considering the parameters as random variables, the distributions of the variables are seen as the normal distribution. The parameters of the normal distributions fit the value shown in Table 1. The simulations were repeated five hundred times.
The possible positions scatter points of the minimum rotation angle path with only the forward moving error coefficient k s variable are shown in Figure 15a. The possible positions of the scatter points of the minimum average-position-error path with only the forward moving error coefficient k s variable are shown in Figure 15b. The possible positions of the scatter points of the minimum forward moving distance path with only the forward moving error coefficient k s variable are shown in Figure 15c.
The possible positions of the scatter points of the minimum rotation angle path with only the rotation angle error coefficient k r variable are shown in Figure 15d. The possible positions of the scatter points of the minimum average-position-error path with only the rotation angle error coefficient k r variable are shown in Figure 15e. The possible positions of the scatter points of the minimum forward moving distance path with only the rotation angle error coefficient k r variable are shown in Figure 15f.
The possible positions of the scatter points of the minimum rotation angle path with only the rotation center lateral offset d r variable are shown in Figure 15g. The possible positions of the scatter points of the minimum average-position-error path with only the rotation center lateral offset d r variable are shown in Figure 15h. The possible positions of the scatter points of the minimum forward moving distance path with only the rotation center lateral offset d r variable are shown in Figure 15i.
The possible positions of the scatter points of the minimum rotation angle path with all error parameters are variable, as shown in Figure 15j. The possible positions of the scatter points of the minimum average-position-error path with all error parameters are variable, as shown in Figure 15k. The possible positions of the scatter points of the minimum forward moving distance path with all error parameters are variable, as shown in Figure 15l.
According to Figure 15, when the rotation angle error coefficient k r and the rotation center lateral offset d r are considered random variables, the position distribution at each target point has greater dispersion.

5.3. Prototype Experiment and the Comparison with the Simulated Result

A prototype experiment was conducted to validate the proposed error model. The prototype was the same as the mobile robot shown in Figure 8. The experimental paths are the characteristic paths shown in Figure 3b,c and Figure 14a. The motion on each path was repeated fifteen times. The result and comparison with the simulated results is shown in Figure 16.
In Figure 16, the blue points represent the simulation’s calculated points, and the points in red represent the points from the prototype experiment.
Figure 16a shows the results comparison of the motion path with the least rotation. Figure 16b shows the results comparison of the motion path with the optimal precision. Figure 16c shows the results comparison of the motion path with the shortest length.
To align the experimental coordinates captured by the motion capture system, the actual start point of the mobile robot is ( 0 , 1100 ) , and the initial pose is ( 0 , 1 ) . The movement of a mobile robot moving from the point ( 0 , 1100 ) to the start point of the path ( 0 , 1000 ) is called the direction calibration movement. The transformations were built to make the coordinates of the start point coincide with the ideal start point ( 0 , 1000 ) , and the transformation angle is determined by the direction calibration movement.
The points in black represent the simulated points with the constant error coefficients. As shown in Figure 16, the experimental points are located around the simulated points.
The data shown in Table 2 verify that the error model simulates the error of the experimental positions compared with the ideal target point positions. The position error is defined as the distance between the theoretical or experimental position and the ideal target position.
As shown in Table 2, the position error generally increases when moving along the path. The original experiment data are available in Table A5, Table A6 and Table A7.
Each error parameter is supposed to fit the normal distribution. The experiment results shown in Table 2 validate that the mean values of the distributions are rational. What is more, the experiment results validate that the proposed three-parameter model can reflect the error of the mobile robot movements.
Considering the error parameters as random variables, the position distribution of the experimental mobile robot at each ideal target position was tested with the same distribution of the simulated positions. The average position error of the entire path is shown in Table 3.
As shown in Table 3, the average position error is the smallest when moving along the path of minimum theoretical error. The path with the minimum forward moving distance corresponds to the largest position error. What is more, the average experimental position errors are smaller than the simulated errors. This may be because the error parameters are seen as completely random. However, the error parameter of adjacent movements may have relative values.

6. Optimal Path with Command Compensation of the Mobile Robot

If the error parameters are known, compensating the motion commands helps to decrease the position error. The movement mode in this article is considered the dual mode. There are only two types of movement, the forward movement and rotation in situ. Corresponding to these two movement types, the forward moving distances, l i , and the rotation angles, θ i , comprise the entire movement commands.
The compensation for the forward moving distance is shown in Equation (48).
l i * = l i k s
where l i * represents the actual forward moving distance command after compensation, l i represents the ideal forward moving distance when considering there is no movement error, and k s represents the forward moving error coefficient.
The compensation for the rotation angle is shown in Equation (49).
θ i * = θ i 2 l i d r w 2 α i 1 k r
where θ i * represents the actual rotation angle command after compensation, θ i represents the ideal rotation angle when considering there is no movement error, l i still represents the ideal forward moving distance when considering there is no movement error, d r represents the rotation center lateral offset, w represents the wheel track of the mobile robot, k r represents the rotation angle error coefficient, and α i 1 represents the initial pose error caused by the last forward movement.
α i 1 = arccos ( 2 cos ( 2 l i 1 d r w 2 ) 5 4 cos ( 2 l i 1 d r w 2 ) )
The initial condition of Equation (50) is
α 1 = 0
The position errors are expected to decrease by compensating for every movement command. The result of the prototype experiment is shown in Figure 17. The simulated positions are also shown in Figure 17.
In Figure 17, the points in blue represent the simulated positions, the points in red represent the experimental positions, and the points in black represent the ideal target positions almost coincident with the experimental position points.
As shown in Figure 17, the error, in reality, is coincident with the simulated positions. The data in Table 4 show the error of the mobile robot after command compensation.
If considering the error parameters as constants, the theoretical simulated position errors are all zero. Comparing the data in Table 2 and Table 4, the compensations of the commands reduce the position error. The original experiment data are available in Table A8, Table A9 and Table A10.
The average position error data of the simulation and experiment are shown in Table 5.
Moving along the minimum error path still has the minimum average position error, and the minimum forward moving distance path corresponds to the largest error. However, the value differences between different paths decrease from the non-compensation experiment.
The prototype experiment verifies that the precision optimal path calculated by the proposed method has better precision.

7. Discussion

Although the structure of the mobile robot shown in Figure 2 is a four-Mecanum-wheel mobile robot, the proposed method of error estimation and precision-driven path planning can be applied to any mobile robot whose motion mode is moving forward and rotation in situ.
The controlling strategy design is going to be universal in robot integration. The integration system developer uses the mobile robot with an entire submodule. It is difficult to adjust the detail of the controlling program of each wheel. Using only the forward moving command and rotation command is common in the integration robot system.
The proposed three-parameter error model contains the forward moving error coefficient, k s , the rotation angle error coefficient, k r , and the rotation center lateral offset, d r . The forward moving error coefficient, k s , reflects one of the errors in forward movement. The actual moving distance is considered linear to the ideal forward moving distance. The distribution of this coefficient was tested as an approximately normal distribution, as shown in Figure 12.
The rotation angle error coefficient, k r , reflects the error of the rotation movement. The actual rotation angle is considered linear to the ideal rotation angle. The distribution of this coefficient was tested as an approximately normal distribution, as shown in Figure 12.
The rotation center lateral offset, d r , reflects the pose error caused by the forward movement. The trajectory shape of forward movement is considered arc-shaped. The distribution of d r is estimated by the arc-shaped trajectory fitting radius. The transformation from the fitted radius to the error parameter d r is shown in Equation (17).
We only need to substitute the nominal value for the wheel track w . That is because for every use of d r , 1 / w 2 comprises the coefficient of d r . No matter the value of w , the value of d r / w 2 is changeless.
The random sequence path movements were used to collect data for estimating the error parameters. All the simulations and experiments used the target points shown in Table A1. The actual moving distance and rotating angle were captured by the motion capture system. However, these realistically observed variables can be calculated by other sensor systems. In contrast to the offline estimation proposed in this article, the parameters’ estimation can be made during the movement, called the online parameters’ estimation. The data of offline estimation are sufficient. As shown in Table A2, Table A3 and Table A4, hundreds of data are used to estimate the error parameters. The number of historical movement data in online estimation is probably less than that in offline estimation. The accuracy of online estimation will be lower than that of offline; therefore, offline estimation is sufficient.
The processes of d r estimation can be improved in future studies. In this study, the radius of the trajectory was fitted first. Then, the distribution of the rotation center lateral offset, d r , was fitted according to the dataset of radii. The fitting of d r can be directly calculated from the trajectory data captured by the motion captured system. However, the value of d r estimated in this article already matches the experimental results, as shown in Figure 16 and Figure 17. The simulated positions, which use the fitted value d r , are close to the experimental positions.
When considering the randomness of the error parameters, the position distribution at each target point is different between the simulated and experimental results. As shown in Figure 16 and Figure 17, the distribution of the simulated results has more randomness than that of the experimental results. This is because the error parameters of adjacent movements may have a relative value in reality, and the prototype experiments are conducted continuously. This also causes the relative value of the error parameters. Conversely, the error parameters are considered totally random in the simulation.
There are many other factors that affect the error of the movements. Firstly, the ground conditions cannot be uniform everywhere. The contact condition between the wheel and the ground affects the error parameters. Secondly, the mechanical clearances at the moment of starting and stopping generate the random motion error. Thirdly, the vibration causes unpredictable motion error. Finally, the trajectories captured by the motion capture system cannot be precise. However, these factors are less of an influence than the influence of the proposed three parameters, k s , k r , and d r .
If the mobile robot moves along the path sequence with the minimum position error, the expected average error is the minimum. The separate simulation is shown in Figure 15a–c; the impact of the forward moving error coefficient, k s , is less on the position error. The numerical fluctuations in k r and d r cause obvious differences in position error. Hence, the path with the minimum position error and the path with the minimum rotation angle are expected to have a smaller position error than that of the shortest path length.
As shown in Table 2 and Table 4, the position error does not continuously increase with the sequence of the path. This property guides the strategy for the localization system. The localization only needs to be performed at the positions with the higher error.
Figure 18 shows the processes of utilizing the proposed error model to obtain a higher localization precision by odometry. The processes are divided into two parts, the offline parameters’ identification and the online commands’ compensation. If the error parameters of a mobile base are unknown, let the mobile base move along random routes and record the actual moving trajectory. The error parameters can be calculated according to this article’s proposed model. The expected initial movements are also required in the parameter calculation. The fitted distributions of the error parameters are used for the online motion compensation.
The movement types for multi-target path tracking are moving forward and rotating. The expected moving distances and the expected rotating angles can be compensated to obtain a higher localization precision by the equations proposed in Section 6.

8. Conclusions

This article first proposed a method to solve the precision-driven multiple-target path planning problem. If a precision function can estimate the localization error of the path with a certain routing sequence, the proposed method can find the optimal routing sequence with the lowest error. Localization error is defined as the distance between the actual and ideal target positions. Moreover, the precision-driven multi-target path planning method works only for mobile robots moving with approximate, known and systematic errors.
A three-parameter odometry error model based on the dual-mode movements was then proposed. The dual modes are the forward movement and the rotation in situ. This model includes three parameters, the forward moving error coefficient, k s , the rotation angle error coefficient, k r , and the rotation center lateral offset, d r . Based on these parameters, the true positions affected by the error parameters can be estimated by a set of actual movement equations.
As each position error can be known according to the specific sequence of target positions, the minimum precision path with the optimal sequence is calculated based on the minimum average position error criterion.
A prototype experiment was designed to validate the proposed error model. The simulated position data matches the experimental position data well. On the prototype, the error parameters can be identified by analyzing the random movements’ actual trajectory. The distribution of the parameters fit the normal distribution well.
As the error parameters are known, the movement commands can be compensated to obtain a high-precision localization in the multi-target path tracking. The prototype experiment results validate the command compensation. The position error is reduced after the compensation. Comparing the three characteristic paths, the path with the minimum theoretical position error was tested with the least position error. What is more, the rotation angle error coefficient, k r , and the rotation center lateral offset, d r , take higher weight on affecting the position error. When the exact value of the error parameters is unknown, moving along the path with the least rotation angle has a lower expected position error than the path with the shortest length.

Author Contributions

Conceptualization, J.J.; methodology, J.J.; software, J.J.; validation, J.J.; data curation, J.J.; writing—original draft preparation, J.J.; writing—review and editing, J.J., J.-S.Z., S.Y.M. and D.M.; visualization, J.J.; supervision J.-S.Z.; project administration, J.J. and J.-S.Z.; funding acquisition, J.-S.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by 2020GQI1003, Guoqiang Research Institute of Tsinghua University.

Institutional Review Board Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest. The funders had no role in the design of the study; in the collection, analyses, or interpretation of data; in the writing of the manuscript; or in the decision to publish the results.

Appendix A

The coordinates of the target points are shown in Table A1. Every simulation and experiment proposed in this article used the points shown in Table A1.
Table A1. Coordinates of the target points (mm).
Table A1. Coordinates of the target points (mm).
NumberxyNumberxyNumberxy
1280.55498.399208.69217.6217572.88733.00
2478.30750.5510908.04707.0218659.59654.93
3364.05979.0211443.7175.281929.41751.03
4302.14898.3212110.49415.2120375.17551.08
5211.2549.6713320.87682.16Start01000
6171.07332.1614981.18317.89End10000
7670.3352.2515288.61621.57
8855.58328.6316897.85457.72

Appendix B

Four random paths with random sequences of the target points were generated for estimating the error parameters of the proposed error model. The paths are shown in Figure A1.
Figure A1. Random generated paths for parameter recognition. (a) The first random moving path. (b) The second random moving path. (c) The third random moving path. (d) The fourth random moving path.
Figure A1. Random generated paths for parameter recognition. (a) The first random moving path. (b) The second random moving path. (c) The third random moving path. (d) The fourth random moving path.
Sensors 23 00517 g0a1
In Figure A1, the points in black represent the target positions. The lines in red represent the moving path for mobile robot. The correspondence data between the expected movement distances and actual movement distances are shown in Table A2. The correspondence data between the expected rotation angles and actual rotation angles are shown in Table A3. The fitted radius data of the forward-moving trajectory are shown in Table A4. Only the trajectories whose captured pulse lengths were larger than 1500 were used for fitting the trajectory radius.
Table A2. Expected movement distances and actual movement distances (mm).
Table A2. Expected movement distances and actual movement distances (mm).
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
10097.79809.73789.08631.07615.79631.07615.78602.78585.8610096.73973.53952.5210098.211048.91022.81
809.73790.71631.07616.99670.29654.97670.29654.12592.43578.5010098.04285.34278.90973.53948.56729.79709.58
631.07617.23670.29655.86476.02462.47476.02463.60723.51708.75595.13581.54810.24787.61285.34278.12656.35640.54
670.29654.06476.02463.22667.21651.28667.21648.87318.45313.54476.02465.10589.69573.47810.24789.58641.02624.25
476.02462.84667.21648.83696.59679.78696.59679.45595.13581.33676.15662.62567.89553.35589.69575.55339.82329.97
667.21650.07696.59679.30625.29608.53625.29607.08476.02464.0796.19393.28411.78402.62567.89553.03438.61427.65
696.59679.20625.29609.26289.73281.09289.73282.69676.15658.84543.77530.22490.37478.13411.78400.16428.08417.77
625.29608.04289.73282.28724.55707.60724.55707.27543.77531.20927.89905.36720.36703.90490.37477.49268.68262.32
289.73282.24724.55706.41753.23733.93753.23734.65927.89907.62638.18622.81339.82330.63720.36701.77567.57553.56
724.55706.59753.23736.95585.52568.96585.52571.51638.18624.41277.07270.03317.22309.09339.82331.84312.37305.06
753.23736.06585.52571.70519.08506.15519.08507.22277.07271.23141.88139.54354.83347.51116.68114.03625.29608.59
585.52573.51519.08506.99663.38648.65663.38647.37101.71100.01530.96520.61530.96517.91317.22308.99661.26644.83
519.08507.26663.38647.41126.05122.46126.05122.80299.98293.03798.71781.08618.64602.83354.83348.12592.43576.84
663.38647.33126.05122.84794.26773.71794.26776.27530.96519.52957.93934.81661.26644.00530.96516.47408.89397.36
794.26775.83794.26775.10101.71100.13101.7199.93798.71780.83853.58834.82879.73857.44618.64601.94815.31793.78
428.08419.41428.08418.84428.08418.46428.08418.78957.93933.01120.56117.08927.89904.45661.26644.92853.51832.41
141.88139.70618.64602.72141.88138.76188.14185.11853.58832.37585.52570.97566551.51879.73858.11835.13813.66
188.14185.03468.97458.36188.14183.44618.64602.12120.56117.86602.78589.04497.73484.64927.89906.33792.64772.84
618.64603.5910098.17618.64603.32468.97458.14585.52572.27592.43576.30618.2603.26566552.30448.89439.12
468.97456.5510096.90468.97458.0810097.29602.78588.03723.51707.401167.41139.15497.73486.37497.73485.22
10097.41809.73790.5510097.7610098.21592.43576.3210097.5010097.63618.2604.82981.65955.33
10098.20631.07616.4710098.24595.13582.76723.51706.37595.13580.83973.53949.591167.41138.421048.91023.95
809.73791.37670.29657.43809.73788.88476.02465.07318.45313.15476.02465.33285.34277.28973.53949.63729.79710.29
631.07615.97476.02462.89631.07616.27676.15661.24595.13580.55676.15657.86810.24789.93285.34277.27656.35639.56
670.29653.41667.21649.63670.29656.92543.77532.61476.02465.09543.77531.23589.69573.31810.24791.17641.02626.48
476.02463.56696.59680.01476.02462.61927.89905.21676.15660.60927.89906.01567.89554.50589.69575.02339.82330.34
667.21651.67625.29609.64667.21650.38638.18623.1196.19393.47638.18625.20411.78401.68567.89552.81438.61429.20
696.59679.86289.73283.36696.59682.01277.07272.40543.77529.48277.07271.80490.37477.79411.78400.38428.08417.00
625.29609.51724.55706.99625.29608.89299.98291.37927.89906.13101.7199.56720.36702.37490.37476.72268.68262.65
289.73283.40753.23737.80289.73282.04530.96519.93638.18625.14299.98292.02339.82329.97720.36702.35567.57554.58
724.55707.81585.52573.97724.55706.00798.71779.90277.07270.88141.88139.11116.68114.10339.82331.11312.37303.23
753.23734.88519.08507.48753.23734.76957.93936.57101.7199.60530.96518.46317.22308.12354.83347.38625.29609.72
585.52571.73663.38648.47585.52569.49853.58832.92299.98292.07798.71777.72354.83346.28530.96515.28661.26645.18
519.08505.44126.05122.24519.08506.06120.56117.58141.88138.04957.93934.38530.96516.76618.64600.89592.43576.91
663.38648.17794.26775.45663.38647.87585.52570.21530.96520.13853.58831.69618.64601.34661.26643.53408.89398.97
126.05123.23101.7199.81126.05123.59602.78589.45798.71779.55120.56117.39661.26645.18879.73856.41815.31791.94
794.26774.59428.08419.12794.26772.12592.43578.60957.93932.98585.52571.88879.73858.38927.89904.51853.51832.91
101.71100.12618.64601.68101.7199.19723.51705.84853.58834.70602.78589.58927.89904.20566550.48835.13815.25
428.08419.01468.97458.74428.08416.09141.88139.48120.56116.95592.43576.43566551.90497.73486.63792.64771.19
188.14183.6510098.44141.88138.82530.96519.40585.52571.15723.51707.51497.73486.35618.2604.23448.89439.08
618.64603.1810097.31188.14184.55798.71779.88602.78587.3210098.14618.2603.061167.41138.10497.73486.80
468.97456.92809.73791.09618.64603.62957.93934.01592.43576.73973.53952.281167.41139.92973.53947.39981.65954.97
809.73791.82631.07616.34468.97459.06853.58834.89723.51706.67285.34277.3710097.11285.34276.211048.91021.95
631.07616.63670.29655.47809.73789.05120.56117.48318.45313.15810.24789.63973.53951.80810.24790.20729.79710.41
670.29654.97476.02462.45631.07615.92585.52570.5210097.85589.69575.69285.34279.07589.69573.28656.35638.43
476.02462.95667.21649.42670.29656.88602.78589.31595.13582.18567.89554.32810.24788.12567.89552.72641.02626.01
667.21650.00696.59679.64476.02463.32592.43575.76476.02465.87411.78401.59589.69573.94411.78402.33339.82332.02
696.59680.37625.29610.75667.21649.28723.51706.56676.15658.95490.37479.22567.89553.01490.37476.50438.61426.73
625.29610.80289.73284.21696.59682.36595.13581.91543.77529.64720.36704.65411.78401.19720.36700.77428.08418.40
289.73281.84724.55708.30625.29608.89476.02464.85927.89906.92339.82330.60490.37478.93339.82331.69268.68263.46
724.55707.93753.23733.78289.73282.18676.15659.50638.18624.51116.68114.66720.36703.65116.68114.88567.57554.87
753.23734.30585.52570.62724.55705.9696.19394.20277.07271.81317.22310.12339.82330.38317.22307.05312.37302.64
585.52569.97519.08506.35753.23735.11543.77529.68299.98292.95354.83347.10317.22308.21354.83346.36625.29608.88
519.08505.96663.38649.30585.52571.91927.89906.14141.88138.75530.96519.24354.83347.69530.96515.31661.26646.31
663.38649.33126.05122.80519.08504.54638.18625.08530.96519.24618.64600.58530.96517.28618.64601.57592.43576.44
126.05123.17794.26775.08663.38647.65277.07269.85798.71780.18661.26645.24618.64605.14661.26643.72408.89398.89
794.26774.02101.71100.13126.05123.18299.98292.43957.93934.04879.73857.89661.26645.15879.73857.34815.31795.86
101.7198.95428.08418.13794.26774.21141.88139.16853.58833.01927.89905.61879.73857.13927.89905.01853.51833.18
428.08417.37141.88139.32101.7198.39530.96517.70120.56117.24566552.36927.89904.48566551.72835.13815.27
141.88139.17618.64603.56428.08417.75798.71780.75585.52573.76497.73486.91566551.96497.73485.67792.64771.82
188.14184.96468.97458.27618.64602.39957.93933.28602.78587.67618.2603.56497.73483.31618.2603.32448.89436.06
618.64603.0110097.84468.97460.27853.58831.77592.43578.341167.41138.59618.2604.721167.41138.43497.73485.76
468.97457.4910098.2710098.31120.56118.54723.51707.9510097.391167.41139.5710097.23981.65955.18
10097.49809.73790.08809.73788.31585.52572.78318.45311.6410096.9210096.9210097.7110098.03
Table A3. Expected rotation angles and actual rotation angles (rad).
Table A3. Expected rotation angles and actual rotation angles (rad).
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
Ideal
Distance
True
Distance
−0.261−0.2571.2851.280−1.721−1.7311.2851.2702.9222.9121.3041.3102.7332.703−0.995−0.9912.2632.248
−2.266−2.280−1.351−1.3341.2851.271−1.351−1.348−2.996−3.0112.1372.1382.1432.151−3.064−3.056−2.976−2.970
2.7202.716−0.261−0.255−1.351−1.337−0.261−0.2631.8641.8332.4412.460−0.995−0.9851.7301.723−2.387−2.373
2.1722.179−2.266−2.296−2.266−2.304−2.266−2.2631.3041.3262.5412.554−0.219−0.2232.7002.7032.6382.647
2.9212.9182.7202.7322.7202.7162.7202.7032.1372.1481.2601.254−3.064−3.0461.7181.718−2.390−2.369
−1.798−1.8062.1722.1622.1722.1562.1722.1782.4412.438−1.512−1.5271.7301.719−2.670−2.674−2.428−2.436
−2.056−2.0562.9212.9072.9212.9232.9212.9432.5412.557−2.315−2.3242.7002.716−1.422−1.416−2.289−2.296
0.6000.604−1.798−1.794−1.798−1.795−1.798−1.8091.2601.2601.7031.7091.7181.730−2.421−2.4133.1013.096
−2.288−2.286−2.056−2.058−2.056−2.056−2.056−2.056−1.512−1.5502.9912.992−2.670−2.6952.1582.1542.7412.719
−2.250−2.2980.6000.6010.6000.613−2.288−2.258−0.589−0.589−2.702−2.734−1.422−1.421−2.489−2.4861.0481.033
−2.792−2.790−2.288−2.268−2.288−2.277−2.250−2.264−2.315−2.3341.1431.161−2.421−2.433−2.326−2.3172.9582.961
2.7882.754−2.250−2.286−2.250−2.306−2.792−2.7971.7031.7010.6060.6132.1582.177−1.187−1.169−1.968−1.998
1.6481.662−2.792−2.791−2.792−2.8002.7882.7682.9912.9802.6322.631−2.489−2.4923.0313.026−1.560−1.553
2.5162.5142.7882.7792.7882.7551.6481.658−2.702−2.664−0.537−0.552−2.326−2.3432.7552.789−2.770−2.774
0.7150.7201.6481.6541.6481.6482.5162.5141.1431.141−1.001−0.995−1.187−1.183−2.771−2.7702.0131.997
1.4251.4252.5162.5212.5162.5130.7150.7140.6060.6002.4292.4443.0313.015−2.719−2.7182.8652.885
2.4612.4610.7150.7170.7150.7051.4251.4242.6322.6152.9222.9192.7552.757−2.773−2.7622.7622.772
2.7752.7841.4251.4381.4251.4322.4612.479−0.537−0.545−2.996−2.997−2.771−2.761−1.580−1.5862.1222.095
−2.533−2.5402.4612.4612.4612.4522.7752.787−1.001−0.9781.8641.879−2.719−2.7402.7332.6902.4012.396
−1.721−1.7002.7752.7972.7752.772−2.533−2.5472.4292.4111.3041.281−2.773−2.7682.1432.165−1.966−1.963
1.2851.265−2.533−2.542−2.533−2.536−1.721−1.7112.9222.9172.1372.137−1.580−1.602−0.995−0.974−0.437−0.436
−1.351−1.338−1.721−1.694−1.721−1.7031.2851.279−2.996−2.9992.4412.4362.7332.727−3.064−3.0672.2632.262
−0.261−0.2571.2851.2771.2851.291−1.351−1.3501.8641.8432.5412.5512.1432.1681.7301.722−2.976−2.984
−2.266−2.293−1.351−1.346−1.351−1.348−0.589−0.5871.3041.2951.2601.262−0.995−0.9772.7002.709−2.387−2.393
2.7202.720−0.261−0.258−0.261−0.264−2.315−2.3302.1372.149−1.512−1.538−0.219−0.2171.7181.7392.6382.645
2.1722.162−2.266−2.251−2.266−2.2851.7031.7052.4412.444−0.589−0.577−3.064−3.075−2.670−2.685−2.390−2.390
2.9212.9352.7202.7092.7202.7082.9912.9932.5412.555−2.315−2.3281.7301.701−1.422−1.410−2.428−2.413
−1.798−1.8052.1722.1842.1722.171−2.702−2.7181.2601.2541.7031.7082.7002.715−2.421−2.432−2.289−2.292
−2.056−2.0622.9212.9582.9212.9341.1431.146−1.512−1.5432.9912.9951.7181.7332.1582.1623.1013.106
0.6000.611−1.798−1.802−1.798−1.7980.6060.608−0.187−0.191−2.702−2.725−2.670−2.689−2.489−2.4822.7412.734
−2.288−2.259−2.056−2.064−2.056−2.0692.6322.654−0.589−0.5961.1431.148−1.422−1.416−0.185−0.1851.0481.064
−2.250−2.3030.6000.6010.6000.593−1.001−1.001−2.315−2.3170.6060.611−2.421−2.418−2.326−2.3152.9582.969
−2.792−2.796−2.288−2.263−2.288−2.2722.4292.4291.7031.7222.6322.6512.1582.174−1.187−1.170−1.968−1.963
2.7882.778−2.250−2.279−2.250−2.2642.9222.9092.9912.991−0.537−0.543−2.489−2.4993.0313.035−1.560−1.556
1.6481.653−2.792−2.799−2.792−2.804−2.996−3.000−2.702−2.713−1.001−0.992−2.326−2.3172.7552.763−2.770−2.786
2.5162.5192.7882.7962.7882.7581.8641.8421.1431.1462.4292.421−1.187−1.183−2.771−2.7712.0132.017
0.7150.7161.6481.6721.6481.6631.3041.2950.6060.6132.9222.9253.0313.044−2.719−2.7212.8652.852
1.4251.4032.5162.5072.5162.5172.1372.1422.6322.628−2.996−2.9992.7552.748−2.773−2.7802.7622.747
2.4612.4620.7150.7231.4251.4142.4412.454−0.537−0.5261.8641.866−2.771−2.764−1.580−1.5822.1222.090
2.7752.7721.4251.4272.4612.4732.5412.565−1.001−1.0071.3041.314−2.719−2.7142.7332.7232.4012.384
−2.533−2.5192.4612.4532.7752.7881.2601.2542.4292.4242.1372.135−2.773−2.7772.1432.155−1.966−1.982
−1.721−1.6982.7752.757−2.533−2.533−1.512−1.5222.9222.9352.4412.447−1.580−1.583−0.995−0.991−1.027−1.055
1.2851.270−2.533−2.536−1.721−1.724−1.001−0.986−2.996−2.9992.5412.5392.7332.713−3.064−3.0952.2632.257
−1.351−1.339−1.721−1.7101.2851.2622.4292.4141.8641.8431.2601.2512.1432.1421.7301.711−2.976−2.977
−0.261−0.2641.2851.272−1.351−1.3402.9222.9211.3041.309−1.512−1.543−0.995−0.9832.7002.699−2.387−2.387
−2.266−2.286−1.351−1.335−2.266−2.294−2.996−2.9872.1372.147−0.219−0.219−3.064−3.0701.7181.7262.6382.646
2.7202.719−2.266−2.3042.7202.7211.8641.8532.4412.457−3.064−3.0731.7301.719−2.670−2.666−2.390−2.377
2.1722.1732.7202.7122.1722.1731.3041.2982.5412.5411.7301.7122.7002.703−1.422−1.433−2.428−2.412
2.9212.9242.1722.1732.9212.9202.1372.1351.2601.2572.7002.7191.7181.713−2.421−2.438−2.289−2.291
−1.798−1.7972.9212.949−1.798−1.8242.4412.450−1.512−1.5451.7181.729−2.670−2.6692.1582.1553.1013.101
−2.056−2.064−1.798−1.801−2.056−2.0652.5412.559−0.589−0.587−2.670−2.681−1.422−1.417−2.489−2.4872.7412.737
0.6000.617−2.056−2.0640.6000.6021.2601.253−2.315−2.339−1.422−1.422−2.421−2.419−0.185−0.1881.0481.043
−2.288−2.2810.6000.611−2.288−2.261−1.512−1.5061.7031.701−2.421−2.4212.1582.158−2.326−2.3172.9582.981
−2.250−2.262−2.288−2.265−2.250−2.278−0.589−0.5732.9913.0092.1582.163−2.489−2.503−1.187−1.174−1.968−1.990
−2.792−2.789−2.250−2.282−2.792−2.795−2.315−2.321−2.702−2.720−2.489−2.492−2.326−2.3303.0313.012−1.560−1.554
2.7882.757−2.792−2.8072.7882.7701.7031.7111.1431.135−0.185−0.184−1.187−1.1622.7552.763−2.770−2.772
1.6481.6622.7882.7881.6481.6722.9912.9890.6060.605−2.326−2.3153.0313.023−2.771−2.7762.0132.027
2.5162.5161.6481.6652.5162.506−2.702−2.7042.6322.612−1.187−1.1912.7552.772−2.719−2.7182.8652.866
0.7150.7152.5162.5130.7150.7301.1431.152−0.537−0.5433.0313.026−2.771−2.769−2.773−2.7742.7622.753
1.4251.4400.7150.7211.4251.4270.6060.612−1.001−0.9932.7552.760−2.719−2.740−1.580−1.5772.1222.121
2.4612.4411.4251.4342.4612.4612.6322.6332.4292.431−2.771−2.763−2.773−2.7772.7332.7132.4012.397
2.7752.7702.4612.4552.7752.772−0.537−0.5432.9222.912−2.719−2.715−1.580−1.5762.1432.159−1.966−1.990
−2.533−2.5422.7752.755−2.533−2.534−1.001−0.991−2.996−3.003−2.773−2.7782.7332.719−0.995−1.010
−1.721−1.679−2.533−2.537−1.721−1.6972.4292.4271.8641.874−1.580−1.5932.1432.180−1.027−1.053
Table A4. Fitted radius of forward-moving trajectory (mm).
Table A4. Fitted radius of forward-moving trajectory (mm).
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
Fitted
Radius
−28,029.7−19,449.0−33,788.8−11,430.1−25,462.9−25,215.0−8146.3−13,963.1−14,818.2−8376.2
−22,911.8−31,819.5−22,466.3−22,694.8−11,062.5−35,623.9−31,148.0−3123.0−30,178.9−8405.2
−24,242.3−26,716.3−4471.8−23,169.3−12,850.5−34,830.9−21,131.2−20,201.8−18,567.2−13,766.4
−18,521.0−22,575.7−32,676.7−29,530.8−21,853.9−23,692.1−33,997.5−27,544.4−23,634.2−13,299.6
−30,536.7−17,972.2−24,614.5−17,959.6−24,801.8−19,994.6−21,647.1−36,128.8−27,933.3−38,306.7
−32,581.7−29,239.4−11,687.0−29,363.3−49,067.7−22,690.2−47,089.9−37,778.0−42,981.0−28,086.0
−35,707.8−30,478.8−26,447.4−24,564.1−24,467.1−25,509.8−33,334.1−26,938.1−44,137.3−28,784.3
−23,202.8−31,694.9−15,460.4−31,520.8−23,215.6−22,998.1−8102.5−22,826.6−18,737.1−29,612.3
−33,356.9−28,291.7−28,084.5−24,515.2−26,425.0−10,144.4−7689.9−6601.9−8725.7−25,736.0
−28,793.8−27,341.4−27,439.0−16,135.8−36,186.9−32,230.1−26,459.3−12,262.2−21,630.3−9853.3
−2074.4−25,432.9−16,804.3−23,460.3−24,860.5−16,176.3−28,263.9−24,127.8−31,551.3−20,570.0
−27,622.5−15,773.2−27,450.4−27,708.8−18,957.5−43,944.0−46,160.7−17,913.9−34,429.0−25,319.2
−24,741.5−26,772.1−30,891.7−13,994.0−23,233.1−20,809.4−34,134.4−23,721.6−31,076.0−19,690.6
−14,404.2−24,954.1−26,038.9−26,855.5−21,974.7−12,414.0−20,747.2−25,837.1−19,283.4−17,337.4
−27,920.1−18,643.8−22,750.9−12,728.9−22,999.7−31,198.6−19,857.1−45,662.1−25,158.2−4653.2
−16,375.3−30,051.7−34,217.5−29,095.7−22,666.4−41,867.0−9572.0−42,742.6−1709.6−35,377.4
−25,025.4−18,572.8−20,947.7−22,759.5−23,114.4−27,407.7−15,143.9−19,513.1−16,843.3−40,213.0
−36,564.9−29,062.4314.5−26,880.4−24,236.3−22,158.5−23,791.5−23,455.2−30,212.7−36,098.3
−21,071.4−25,047.0−26,762.9−16,121.7−27,389.2−19,344.9−3486.4−33,951.0−13,644.6−32,064.7
−14,536.9−23,574.9−25,454.7−28,064.5−14,956.5−23,536.6−24,270.6−31,759.8−23,367.0−10,088.8
−30,062.3−10,971.8−16,692.6−33,144.4−14,519.5−21,213.1−19,052.6−34,518.9−19,512.1−14,106.6
−26,450.8−35,453.0−27,854.4−29,675.7−36,844.8−26,071.8−42,862.3−19,559.0−47,778.2−35,928.8
−16,920.9−38,220.7−18,893.6−23,825.1−20,598.8−8665.3−42,336.3−17,085.8−37,537.2−29,202.3
−27,995.0−26,497.3−28,452.5−30,894.3−46,785.6−39,054.1−18,257.4−6070.2−19,752.7−27,516.7
−18,383.1−18,263.5−8509.4−27,409.5−26,751.5−19,609.9−10,016.0−4576.6−14,120.9−29,545.0
−38,311.9−32,583.4−22,902.0−29,128.6−17,356.3−50,699.8−22,028.4−32,414.2−31,735.2−19,276.2
−27,702.4−26,703.2−18,375.0−24,356.2−32,357.1−24,463.5−31,424.5−21,092.7−28,462.7−2848.4
−24,855.8−30,109.1−26,561.8−28,256.7−31,011.8−19,693.7−356.8−27,494.3−36,185.7−9919.8
−17,696.5−26,289.6−31,696.7−8446.7−25,313.1−30,729.5−30,267.8−21,843.3−21,908.3−18,675.1
−26,382.7−11,467.0−27,740.0−29,160.3−19,150.5−37,821.0−27,179.6−46,309.4−22,070.9−20,116.4
−42,357.1−38,478.7−27,482.4−20,790.4−22,748.7−30,800.2−20,232.1−39,166.7−21,679.1−21,634.2
−24,228.1−17,539.3−33,350.1−47,320.3−27,614.2−22,166.1−18,538.1−21,155.0−11,565.6−20,379.7
−26,010.0−29,688.0−34,966.3−21,440.9−26,858.8−21,441.7−8664.0−5385.7−10,985.4−5512.9
−24,303.9−12,442.1−7097.3−1519.9−29,038.4−28,027.4−12,142.8−25,899.2−14,446.1−40,010.2
−32,753.0−26,515.0−30,216.8−31,183.9−18,401.4−21,952.6−28,451.5−27,826.6−7335.8−31,790.8
−3302.1−15,383.8−29,327.6−51,260.9−29,124.7−36,096.9−18,543.8−40,983.4−8306.4−30,695.9
−31,098.2−31,479.8−16,120.1−25,362.1−16,983.6−26,573.0−26,454.3−37,930.5−7459.9−28,732.3
−28,045.8−25,370.3−24,241.6−569.6−42,419.8−21,805.8−23,504.9−26,246.1−7931.5−10,861.7
−14,136.9−20,589.8−16,602.8−20,411.0−27,160.1−19,604.4−49,422.1−21,606.9−8968.3−15,103.1
−24,708.9−24,253.7−28,946.7−21,676.5−22,617.6−6704.7−39,811.7−7455.7−8912.5−32,896.1

Appendix C

The original experiment position coordinates are shown in Table A5, Table A6 and Table A7. The experiments were performed with no compensation for the movement commands.
Table A5. Experiment data when moving along the path with the optimal precision. The movement commands have not been compensated (mm).
Table A5. Experiment data when moving along the path with the optimal precision. The movement commands have not been compensated (mm).
Sequence 123456789101112131415
1x0.00.00.00.00.00.00.00.00.00.00.00.00.00.00.0
y1000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.0
2x30.829.627.929.727.828.929.032.227.131.124.329.230.929.325.1
y756.5755.8755.9757.4755.9756.6756.5757.1755.6756.7755.5756.0755.7756.3755.9
3x111.7111.9103.3105.7102.2104.5105.2110.799.4111.392.7104.9108.8105.597.8
y427.8427.3425.2426.7425.4425.1426.6426.7424.1427.6423.5425.6424.8424.9424.5
4x171.9171.7161.1164.8160.7163.1164.5170.9157.6170.2149.1163.2167.1164.4155.3
y345.6345.7341.6343.1342.7343.4343.6344.3340.8345.7339.1342.7342.1343.2340.3
5x209.1208.1195.4198.6193.7198.6199.3205.4190.3207.4180.3198.5201.1199.5188.1
y232.9233.2228.6231.0229.0230.4230.0231.6227.4232.4225.5229.3229.1228.6227.5
6x209.3208.8191.6195.5191.6193.9196.7203.6186.8206.0172.7197.5196.1196.7182.6
y70.569.566.568.066.566.866.967.963.970.161.767.965.366.364.5
7x437.7438.6422.1425.9421.8423.3427.5435.0416.4434.3402.9427.6426.5427.0413.9
y89.289.779.484.380.380.681.784.975.888.070.282.679.383.775.8
8x658.7659.1642.7646.2641.6643.6646.6655.0635.7656.5622.0648.3646.4649.2631.3
y61.460.947.252.147.847.150.353.739.060.832.453.345.555.138.4
9x848.7849.3839.3843.9835.5840.9841.4849.6834.9849.0824.2843.6844.5842.0834.1
y326.1326.7306.6312.6310.5308.1311.6315.6298.6323.4289.7313.9305.6317.3294.9
10x968.9969.8958.5963.2955.3961.2960.9969.5954.4968.7943.4963.1964.3962.6953.8
y311.8310.7289.5294.5293.1289.6292.8298.2279.5308.8269.1297.5287.0299.3273.5
11x896.8894.4886.0893.2882.6889.7889.1898.4885.6894.5876.6891.4892.7891.6886.5
y454.1452.9433.5438.5437.0432.8437.6441.8422.9450.9415.0441.2429.4443.9418.9
12x918.3916.6913.2920.2908.8917.1917.4922.9911.9916.9909.6915.9917.7919.9919.4
y695.5695.8674.0679.3678.6674.1678.9683.5663.5692.6655.7683.1671.4685.7657.9
13x672.4670.6667.6673.9659.7670.8669.5677.0665.2672.0662.8670.0670.0672.7672.3
y656.8653.8643.1646.7644.9641.7642.1648.6632.0651.5626.8648.5635.9651.6627.5
14x593.9591.3590.0596.5581.7594.3592.5598.2586.9591.5585.6592.1592.4595.0594.4
y738.5736.1727.1729.2727.3724.0725.6730.0715.0733.0709.8730.5716.4734.3710.8
15x503.2500.5498.8504.8491.2502.5501.4505.7496.2501.1494.0500.7499.4503.6502.3
y763.2759.4753.6753.4752.8750.6748.3754.6741.3756.7736.6756.4740.2758.2736.1
16x408.0402.1406.3414.1400.0411.3404.4411.6408.8403.9408.7410.1406.2408.6414.4
y992.6987.6983.3984.7983.9981.7978.1984.1973.5986.9969.0988.0971.4988.8967.9
17x337.1333.5336.6344.0330.1342.7336.2342.4337.2335.0336.4341.2337.2339.5345.7
y917.9912.1909.4912.7909.7908.9901.7910.9903.0911.2898.9913.2896.9913.0896.1
18x339.0337.9337.7343.1327.6340.5338.2346.1334.1336.7329.8338.1339.3342.0342.6
y704.5699.8694.6698.4695.7694.6688.8696.9688.4695.9685.1699.0683.3700.1681.2
19x302.9301.6300.6305.1289.6302.9301.4309.0295.5300.9289.8299.8303.9304.2305.7
y649.0642.5639.1643.0639.1638.8632.1639.7633.8640.2630.1644.2626.7643.2625.0
20x283.4285.9281.7285.0270.2282.6284.3292.4273.5281.1267.7279.0286.4287.1284.8
y527.9522.6518.4522.4520.2519.8512.3519.6513.6519.1511.1523.9506.4522.8506.3
21x382.2382.5380.1384.7369.3381.8382.9391.7374.1379.3367.6377.7384.2384.6384.9
y570.0564.3560.1563.1558.0561.9554.4562.3552.4560.5549.5562.8549.6564.3544.7
22x938.2947.0926.5924.2906.6929.1935.9950.7914.1926.9901.8913.0945.1938.5924.8
y−19.8−19.0−39.2−44.6−49.3−37.2−38.7−25.9−52.4−37.0−61.6−46.6−36.2−28.0−59.7
Table A6. Experiment data when moving along the path with the least rotation. The movement commands have not been compensated (mm).
Table A6. Experiment data when moving along the path with the least rotation. The movement commands have not been compensated (mm).
Sequence 123456789101112131415
1x0.00.00.00.00.00.00.00.00.00.00.00.00.00.00.0
y1000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.0
2x23.920.224.029.629.329.526.625.930.424.530.427.824.924.226.2
y757.5755.0755.8756.4756.6756.4755.2757.8755.3756.2755.8756.8756.0756.8756.0
3x96.386.894.6108.3111.1109.5100.2101.6109.596.1108.4106.196.896.198.0
y425.6423.5423.9425.9427.7427.3424.5428.5427.8425.9426.6426.6424.6426.0426.2
4x153.0143.0152.8167.7170.9168.1158.1159.5167.1153.4166.7164.5154.2153.0155.8
y342.2338.1338.4343.7346.5345.0340.8344.9345.7341.8343.7345.5341.1342.0342.6
5x409.2397.0406.0428.8435.2434.0415.5416.2429.3409.9426.9427.7410.0405.1409.0
y82.074.974.385.693.894.282.887.191.682.585.989.980.878.179.0
6x629.2617.6627.6649.7657.9657.9638.0636.7651.7631.8648.6648.4630.1624.8629.2
y45.740.340.257.967.972.751.356.864.351.659.062.345.040.442.5
7x830.0814.7820.8840.7847.4839.8830.7829.0840.8824.5836.7839.3828.7824.3826.8
y304.2301.0305.5324.1336.7343.4313.1320.2328.3311.9323.0326.4304.0299.0301.5
8x879.1863.8865.5883.5891.8882.5877.6876.1886.3873.8883.1885.7878.3874.9878.3
y425.3424.3431.3448.6461.8470.7439.6444.2452.8435.8449.4449.8426.1420.3424.8
9x909.5890.0886.1903.9909.5890.7898.0899.1905.7897.2901.0907.7908.3904.6907.5
y669.1668.4674.6693.4705.5715.5682.1686.8696.3679.1690.9694.6669.6663.0667.3
10x404.9379.9367.4382.1385.9357.3383.1384.3389.4382.8380.8396.2406.8400.3400.6
y981.9973.7965.2980.6988.3978.3978.5981.5991.0973.2976.8997.0987.5975.3979.2
11x334.4311.0301.3316.1320.6295.4317.2316.9323.7314.9317.9327.7336.4329.4332.9
y908.6900.1889.0903.4910.9900.0901.9905.6914.7896.9898.8922.1915.2902.1906.5
12x373.3352.4360.2372.2382.1361.3366.7363.9372.0361.6374.6368.2370.8368.8367.8
y564.0551.9543.1558.1564.9556.1554.7558.7570.0549.9554.5576.3569.5554.7557.8
13x163.9147.6178.9182.3200.8192.2172.5162.5172.7162.8189.3157.5156.3152.9148.1
y95.579.763.379.183.872.178.487.795.076.475.2107.8101.490.094.8
14x181.4166.0187.3193.4209.5193.8185.5177.4186.1176.4199.8176.2177.1174.4171.1
y256.4241.9226.1241.6247.2234.2242.9249.5257.3238.7239.7269.5263.3250.3255.3
15x283.7264.1273.5285.1295.5273.8283.9273.6282.0273.1286.9281.8284.3283.4279.6
y519.4507.0496.4510.1516.3505.3507.8515.3522.3502.9506.5530.2525.4509.9516.0
16x307.3284.6288.0303.0312.7286.9302.9295.3303.4292.8302.9305.8309.5310.5304.8
y638.5626.4616.0628.5637.3626.6628.1635.3641.3623.2625.6647.1643.2628.8634.9
17x348.3324.4323.3338.6347.7320.1340.3332.8340.8329.7337.7346.3351.5352.0345.0
y691.7682.1672.7684.6693.3683.9684.5689.0697.8679.7682.6701.5696.8681.2688.7
18x509.5484.2482.0499.8504.9475.7499.8491.3502.2489.3497.1507.3512.6513.9507.3
y736.7729.0727.8736.7751.3743.5734.5737.0747.5730.2738.8744.3740.0721.2728.1
19x597.5574.5572.9588.2595.5568.2590.2581.6591.2578.5586.0595.6600.7602.0595.1
y705.2700.7703.6708.6726.6720.7708.0708.5718.9702.0712.7712.4708.1688.4694.8
20x669.6646.9651.9664.5674.8646.2662.0654.6664.2651.1660.3665.6669.3670.3665.0
y615.5612.9619.3620.8642.4638.6619.9621.2630.5615.6627.4621.7617.8595.9602.8
21x919.9905.6931.2935.6954.8934.6928.6917.1921.1917.0932.3911.1915.4912.0906.3
y237.5238.7260.9256.0284.7287.9250.8252.5256.1248.1263.0240.1234.3212.1219.1
22x880.3869.6913.5912.0943.3927.4899.0889.6883.5888.1907.4866.0868.0861.1858.9
y−68.1−71.4−49.8−52.8−25.5−24.0−60.1−57.4−50.8−60.9−45.1−67.5−72.2−93.7−87.4
Table A7. Experiment data when moving along the path with the shortest length. The movement commands have not been compensated (mm).
Table A7. Experiment data when moving along the path with the shortest length. The movement commands have not been compensated (mm).
Sequence 123456789101112131415
1x0.00.00.00.00.00.00.00.00.00.00.00.00.00.00.0
y1000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.0
2x26.725.523.328.724.029.523.224.127.332.524.627.227.924.924.9
y755.9755.9755.9755.8755.5756.3755.4756.5757.1756.4756.1756.1756.7755.2756.1
3x297.3299.5295.5299.8294.9299.2296.6297.2299.3300.9297.7297.4299.6296.6295.3
y895.8897.8897.1898.8896.4899.3891.1890.9899.0903.2895.4900.1898.4898.5899.3
4x360.2362.0358.3361.1357.8361.0360.1361.0360.7360.7360.6358.5360.7358.8358.3
y975.9974.4974.0978.1974.2978.0967.9967.4976.2981.9971.7978.4976.0975.8977.9
5x464.1466.8456.4470.1462.2468.5461.3462.4463.6474.1461.5462.1468.4458.5464.0
y750.0748.9747.0755.4750.1755.7741.6740.7752.4761.3745.7752.5751.9748.5750.7
6x556.8560.4549.1561.4556.5562.1553.4555.1557.8567.8554.0556.1562.8551.3558.2
y729.1729.1723.3737.8730.8735.8720.6720.3732.7745.0724.3733.3732.5726.8732.5
7x636.8642.9628.4642.6639.1644.1634.2634.5640.5651.7635.9637.5643.8634.6637.6
y648.6649.3642.5658.5652.4655.7639.3638.7652.0666.5642.8654.0653.1645.8653.8
8x882.5888.3874.1888.0882.5889.1879.4880.9884.9895.4880.9882.9889.3878.1884.0
y686.4691.7674.7701.4695.5695.6680.0676.9695.6717.4685.5696.4695.6686.7691.9
9x853.9863.5842.2869.5863.1863.7854.6854.7864.3879.5860.4864.0865.8854.4857.6
y443.6449.2434.2458.2454.3453.4437.2434.5454.4474.0442.0452.6452.4443.5448.2
10x924.1934.9911.7941.3939.8934.2928.0926.2940.7956.2934.3940.1938.7928.7929.7
y299.8304.5291.5316.3312.9309.1295.6291.8312.3334.3301.2312.5310.5301.9306.4
11x804.3814.3792.3821.4819.7813.8807.5805.6819.9835.0813.5817.0817.5806.5808.0
y323.4325.5315.3334.6330.4332.5314.6313.9333.2352.1319.3334.0329.2324.2328.9
12x365.3361.7354.8369.0363.4373.6357.7358.1366.4381.0356.9367.6364.9354.4362.5
y594.6574.7587.5584.9569.9600.4568.6572.3581.0597.5563.5584.7579.9574.5587.3
13x328.5321.0318.0327.4319.1337.0317.7320.5324.3338.1314.0326.3326.3314.0323.6
y729.8707.5722.6717.7701.6736.3700.9706.2712.9730.3694.4718.1712.9707.2721.3
14x286.7282.1275.7288.1280.7294.1278.3282.4285.8299.5276.6288.3285.7275.3284.9
y674.8647.4664.3662.4644.6681.2645.7650.4653.5672.3636.2657.4655.5647.7662.0
15x261.9264.0252.3267.5265.0270.0257.6258.7269.2282.3258.7269.3265.8256.4262.8
y554.3528.0544.1542.3525.3562.5523.8529.7534.7551.0515.1539.4534.8527.7543.1
16x88.190.177.895.595.495.284.086.197.6110.886.996.593.282.991.2
y499.5464.0487.4479.1456.0505.5464.3470.6467.2485.0452.2474.1474.8466.4480.7
17x132.6142.0126.9145.4146.4142.2132.9134.3147.3164.3136.4148.3144.2132.5141.6
y406.7376.7396.6389.9369.1412.9373.6380.8378.7396.8362.5386.7386.1375.7390.9
18x151.3165.8147.7168.4173.0162.6155.3155.3171.4191.5161.2174.3168.2155.1164.4
y289.5262.0282.1275.0254.2298.3259.3264.7263.3283.8248.7270.8272.5260.0276.6
19x125.7151.2128.2152.8160.5139.5137.5135.8157.1177.3146.0157.7149.8135.7144.7
y129.198.6121.0110.990.6137.095.6101.3102.7120.285.5109.7108.598.0114.4
20x357.0381.9359.4384.1390.4369.9366.7366.7386.9408.8375.9390.3380.5367.6376.5
y113.094.4111.5108.490.7124.487.392.299.0121.282.8107.3100.892.7107.3
21x569.2599.3573.4599.7608.7584.5582.2581.0604.9626.1592.9606.7596.3583.6590.5
y48.643.254.256.245.063.732.035.749.272.934.257.445.039.650.3
22x875.1910.8882.3911.2922.1891.5892.7890.3916.0939.9905.8918.7907.3895.7901.1
y−67.1−50.4−51.5−41.6−45.5−44.4−70.5−69.8−45.3−17.1−59.3−36.9−54.8−59.4−55.4

Appendix D

The original experiment position coordinates are shown in Table A8, Table A9 and Table A10. The experiments were performed by compensating the movement commands.
Table A8. Experiment data when moving along the path with the optimal precision. The movement commands are compensated (mm).
Table A8. Experiment data when moving along the path with the optimal precision. The movement commands are compensated (mm).
Sequence 123456789101112131415
1x0.00.00.00.00.00.00.00.00.00.00.00.00.00.00.0
y1000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.0
2x27.933.029.229.631.829.929.727.822.732.628.426.528.328.622.7
y750.6751.8750.0750.9751.6750.5750.5750.9750.1750.8750.2750.5750.1750.6749.4
3x106.2121.4111.0112.0117.9109.9110.1105.896.8118.8106.1104.2108.1107.396.0
y413.6415.8414.7415.6415.2414.3415.7412.1411.0415.2412.0413.3413.1413.4412.2
4x167.4183.2171.6173.3179.5171.5171.7165.8156.7182.2165.5164.9170.3168.0156.6
y330.6332.2331.4332.8331.4330.3331.2326.7326.6332.2327.2328.7329.7329.8328.0
5x204.6222.2210.1212.9217.9208.4209.7201.6190.8218.5202.5201.5206.9205.9191.9
y215.3220.1217.5218.0218.1215.8217.6212.1211.6218.4213.0214.0216.0215.9213.5
6x206.2224.5212.8215.3220.8210.7210.3200.2188.9220.8201.8202.6209.1207.9191.7
y48.853.451.751.850.849.150.345.645.150.746.747.348.449.445.9
7x441.4458.0446.4449.8454.5443.6445.0435.8424.3454.4436.5437.4443.4442.5427.2
y74.078.577.177.378.874.575.166.864.875.865.771.470.572.067.1
8x668.2684.5672.5675.9681.5670.1671.3661.0650.0681.5662.6663.2670.3668.6651.9
y51.857.553.956.358.553.152.140.337.257.137.247.947.746.440.5
9x852.8870.3857.2858.4865.3854.0855.9851.6842.7863.4855.0849.8856.4856.4843.3
y329.2335.6331.7333.8336.6331.4329.9315.1308.9337.3310.4324.0325.9324.0312.3
10x977.9994.5981.2982.9988.8976.9980.3975.2966.5988.2979.0974.1980.8980.1967.4
y318.0324.8323.0324.4325.8322.2319.6300.6295.7328.2297.0314.5312.8312.7299.6
11x896.5912.1896.9900.5904.0892.7898.1893.5888.6905.2898.8890.6898.8898.6888.8
y460.4465.9463.6464.8467.3463.5460.5442.6439.9468.2439.6456.1455.5454.9442.0
12x907.9918.8903.0906.2910.1899.5905.5909.5904.7910.7913.0898.1906.5910.6902.3
y708.6714.5711.7712.9717.1711.0708.2693.1687.7716.1687.7703.2703.8703.1689.2
13x660.0669.9653.7658.7663.1651.1658.9659.8653.8663.9660.8651.0658.7661.4653.4
y655.6660.0653.5657.5658.4654.3651.5644.9638.8657.6637.2646.0648.1650.2639.6
14x573.1583.8567.2570.8576.6563.3571.1576.9568.6574.6576.0562.8570.7575.8566.3
y733.4737.7729.8733.7735.2729.6728.5724.1717.0733.1715.5721.1725.1727.6717.6
15x477.7489.3471.0475.2480.2467.6476.3480.7474.1479.1480.1467.6475.8478.9471.2
y750.1755.5747.0749.5750.1747.1744.8742.1738.5749.4733.1736.6740.2744.9736.3
16x361.8377.0355.0357.0362.9349.0357.3370.3363.9361.7369.8348.3356.9364.4358.6
y974.2981.8972.9974.3975.5972.4969.5969.7966.7972.2961.3960.0963.4971.1963.1
17x298.8313.4292.9295.1302.8287.3295.0305.9298.6298.3305.1286.8293.9301.2293.3
y890.8901.4889.8891.0893.9889.2886.1890.6886.4888.9882.1875.1880.8889.2881.5
18x322.4337.2313.5321.2328.5310.9319.8323.4313.6325.5320.6311.0320.3320.1312.8
y674.8682.2671.3674.2674.9672.1668.8671.2669.4672.0662.5659.4663.4670.7664.5
19x291.8305.4281.6291.2297.2280.8291.3289.6280.9294.6286.4280.6289.1287.9281.0
y613.1621.1611.1611.9613.0610.8606.1611.7608.7609.1603.5597.2601.0610.0604.0
20x287.8299.6276.3287.0294.1275.9285.9282.3271.3289.8276.9277.3284.7281.5273.0
y489.8497.1486.5488.2488.4486.9481.8486.8486.2486.1479.5474.0477.2485.7480.2
21x383.1394.6373.1381.8387.9370.9380.5378.7367.4385.1374.8371.9378.4376.5368.6
y543.1550.7538.5543.5544.6540.5536.4536.3534.9540.1528.7528.2531.3538.1532.4
22x1026.61028.81003.51027.21029.21009.01024.2997.1984.51025.8989.61015.61015.01003.0995.5
y19.116.4−0.323.019.010.612.2−15.2−20.515.7−30.34.80.3−5.6−10.0
Table A9. Experiment data when moving along the path with the least rotation. The movement commands are compensated (mm).
Table A9. Experiment data when moving along the path with the least rotation. The movement commands are compensated (mm).
Sequence 12345678910111213
1x0.00.00.00.00.00.00.00.00.00.00.00.00.0
y1000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.0
2x28.930.531.433.131.925.332.230.232.632.726.129.430.6
y751.2752.1751.7752.2752.5751.2751.2752.2752.2751.3751.6751.2752.3
3x106.9110.4113.3121.5117.2100.5119.0109.7118.9117.4100.8112.8112.7
y414.7417.2416.8419.2418.9415.6416.7418.2417.6417.1415.7415.9417.0
4x166.5170.6174.7184.5178.6160.0181.0169.8180.5179.4161.2174.9174.7
y330.9333.9335.3337.6335.3331.6335.8335.0335.8333.7330.4334.4333.3
5x434.7442.7447.0458.9453.9427.5456.7443.5453.6452.2429.9447.9445.6
y72.478.979.586.784.272.884.981.083.080.471.381.978.5
6x661.4669.2673.3686.2680.5654.1683.0668.6680.7679.6654.5674.4673.0
y49.056.859.068.064.747.267.659.463.858.845.161.256.2
7x847.4855.4857.6866.2864.8841.7861.5854.2861.5863.6843.2856.8857.3
y324.5332.9336.3348.4343.1322.1348.7335.7343.3336.3320.7338.9333.5
8x890.5897.9899.8906.0904.1883.8899.0894.6900.7904.9885.7897.0897.3
y452.6461.2465.2477.9472.1450.2478.0465.3474.4464.0448.4468.2461.7
9x897.0904.1907.9912.8908.4894.4901.0901.5907.4912.3895.6903.4905.8
y701.4710.6715.8727.4721.0700.5727.6713.8722.9713.5697.5717.7710.6
10x352.0362.0364.9363.0360.9353.9350.7353.9358.7366.7351.9358.2363.6
y963.5976.9983.1981.9975.5970.4977.5972.8979.9971.8965.6978.6975.9
11x290.4299.8301.8303.1300.7290.7291.1293.0298.3304.2289.3297.0300.7
y881.5895.2901.6896.6891.1889.6892.9889.4897.7888.1884.5895.5893.6
12x371.5381.5376.6388.1386.5365.1376.1376.7379.2385.6367.7378.7380.1
y537.2551.0554.3551.3546.8542.0548.4544.2551.9541.8538.0550.3547.5
13x222.7237.9222.2243.0244.1209.6233.5233.7227.4236.9219.3232.8229.3
y35.246.152.449.042.641.744.239.850.539.335.747.546.1
14x217.6231.0220.5235.4237.6208.0227.7228.3222.8230.2214.4227.4225.0
y201.7212.5219.1216.1208.1209.2212.5206.9216.5205.6200.2214.3212.4
15x281.4287.6288.2298.2298.3275.0288.4288.5289.8293.4277.5291.7291.3
y481.1493.1498.5497.6488.9488.5493.6488.1496.0486.4480.8493.5491.8
16x285.4290.5294.6302.6301.2279.6292.9292.6295.9297.3280.5297.3296.5
y604.5616.5621.0619.9612.1611.5616.4611.4619.0610.1603.0616.1615.1
17x314.4318.4326.5333.4330.4310.7323.6321.3327.4328.3310.2328.6327.6
y665.2679.1681.5680.4674.2673.9677.3672.6679.8671.2665.3677.9675.2
18x467.7470.9483.1488.7484.2467.1478.0475.8483.7483.9465.5483.7481.6
y737.8756.6753.1754.1749.7744.3751.5747.0750.5743.0739.4749.5748.4
19x562.2565.0575.4581.8577.2559.8571.1569.9575.9576.9559.4577.8575.8
y723.4744.2737.1739.5736.3728.3736.8731.9732.1727.1724.4734.3733.6
20x651.2653.5660.9670.6666.1644.3658.9657.0661.7664.9645.3664.3662.9
y646.6670.5658.7664.3661.1650.4661.2655.3654.3650.9647.2657.5656.6
21x977.2989.1980.3997.3996.9963.9986.3981.2981.7989.2968.4987.2987.6
y318.3350.2323.4336.3339.4314.0333.3325.3319.1321.1314.7325.3325.8
22x1000.41021.6998.31023.91028.9981.51011.11006.21002.81014.5990.21009.21011.8
y2.135.27.219.823.1−1.018.59.22.95.0−1.49.39.6
Table A10. Experiment data when moving along the path with the shortest length. The movement commands are compensated (mm).
Table A10. Experiment data when moving along the path with the shortest length. The movement commands are compensated (mm).
Sequence 123456789101112131415
1x0.00.00.00.00.00.00.00.00.00.00.00.00.00.00.0
y1000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.01000.0
2x32.330.431.429.925.124.027.227.827.826.329.530.327.025.729.7
y752.6751.0752.0750.9749.8751.2752.2750.4750.7751.0750.8750.8750.4751.4751.0
3x304.6303.5304.6303.0301.6301.8304.2303.7303.2301.1304.0302.7304.4301.1303.9
y905.3903.7902.1901.7893.2892.2896.8896.6896.7898.9901.5903.2893.9897.3900.7
4x364.0364.4365.2364.3365.3365.5366.5364.8365.7363.9364.8362.5368.1364.1365.3
y988.0986.2983.7983.4972.4972.4976.4978.8978.1979.6982.3985.1973.8977.0983.5
5x482.4479.2479.2482.5473.0471.8474.2479.4477.7476.8479.2479.7474.1474.3475.9
y764.7761.4757.1758.5744.7744.0748.6752.5752.9754.2758.8762.0745.3750.7756.5
6x579.3574.9574.7579.9568.3566.8569.0575.8573.9573.3575.7576.2568.9570.3571.3
y748.7744.3740.1743.8724.0722.6729.4734.6735.0738.6741.5746.8724.8732.4737.9
7x668.3662.2659.2668.5653.7653.0654.4663.6661.7660.0662.9664.8656.8656.3657.7
y672.3666.7660.4667.1644.2642.1651.0656.3657.9661.0664.9669.9646.3653.8661.2
8x916.4911.3908.9915.8903.8902.7905.1910.3910.6910.3912.2913.0905.7906.2907.9
y730.2724.6707.6723.8689.5689.4698.6708.5713.8713.5719.4727.9693.7704.8711.2
9x912.9904.5890.6908.6888.0886.3889.4899.1897.4897.5903.6906.2889.4893.7896.5
y482.9476.2460.7474.4441.7440.3449.9460.7465.7464.2472.2480.1446.2456.1463.3
10x1001.1990.1970.0994.6968.2967.0968.9984.2983.8981.5989.2992.7969.9977.7977.9
y345.2337.1316.6335.9299.5298.2306.6320.4324.8324.4332.9342.0301.9316.0322.5
11x876.4864.8846.9869.7844.6842.8845.1860.0859.6858.3866.6868.8847.6853.6852.5
y352.7349.1330.3344.8315.1315.3324.7334.0336.6337.9343.5351.7318.9329.5336.1
12x391.5382.7373.0384.9374.3370.4373.8379.7377.6377.8382.3381.3373.7373.1377.7
y561.0562.9566.1553.0552.4552.3564.1555.3554.4556.9554.0557.5553.5548.9566.3
13x334.6327.5322.8326.7325.5322.2325.7325.5322.5322.4325.8324.1324.1317.9327.7
y689.8692.5698.4681.1684.0684.7698.0685.7683.8686.2683.9686.3687.0679.1700.1
14x300.3294.5286.5294.7288.3282.9287.2292.0288.4287.8291.0291.0287.3282.3293.2
y627.9630.3637.8617.2626.4625.1636.9623.4623.2624.3621.7622.4626.9616.8639.4
15x297.8286.3276.3291.6275.3270.7274.6285.4283.3283.0284.6287.3276.1275.6281.1
y503.1506.4515.3492.7501.2501.4514.4500.5499.1500.6498.2500.6503.9492.9515.4
16x132.0118.9105.6125.2103.399.8102.5118.6116.8116.4116.8121.3105.1107.5112.1
y414.8423.2435.9405.9427.9422.8438.0415.8412.6413.7411.7411.5425.6408.7435.3
17x197.8180.1164.8189.3161.1156.5160.1181.5178.6177.4178.6184.9163.8167.4170.5
y334.1337.8348.6322.7341.5335.7352.2330.6329.1329.5329.3328.9339.8323.2349.4
18x241.0217.8199.2228.8193.0190.5193.3220.0218.0217.2217.3225.7197.7204.2207.4
y222.7224.3234.9210.8226.9221.0235.7216.7215.7215.7215.5215.9225.0209.3235.5
19x251.2220.0198.5233.5186.6186.8189.9222.9224.8222.4222.2231.4196.4208.2208.0
y54.856.967.744.261.654.568.850.550.250.049.748.558.643.068.4
20x484.1453.4432.9467.0421.2420.3426.1457.7457.6454.9457.2466.1430.6442.2440.3
y91.281.288.572.073.571.685.180.080.677.078.380.777.869.890.6
21x710.4680.7659.1693.4645.2644.6651.3684.4684.6681.5682.8692.8656.5668.1667.9
y78.457.660.052.539.041.955.059.864.659.958.664.549.848.164.7
22x1042.31009.3985.51022.4971.3973.1978.41013.11014.71013.61013.31023.7984.8998.3995.8
y40.73.8−2.06.1−32.6−21.9−7.211.524.916.68.422.5−8.5−1.76.6

References

  1. Pandiri, V.; Singh, A. A swarm intelligence approach for the colored traveling salesman problem. Appl. Intell. 2018, 48, 4412–4428. [Google Scholar] [CrossRef]
  2. Pham, T.; Leyman, P.; Causmaecker, P.D. The intermittent travelling salesman problem. Int. Trans. Oper. Res. 2018, 27, 525–548. [Google Scholar] [CrossRef] [Green Version]
  3. Hassoun, M.; Shoval, S.; Simchon, E.; Yedidsion, L. The single line moving target traveling salesman problem with release times. Ann. Oper. Res. 2020, 289, 449–458. [Google Scholar] [CrossRef]
  4. Gelareh, S.; Gendron, B.; Hanafi, S.; Monemi, R.N.; Todosijevic, R. The selective traveling salesman problem with draft limits. J. Heuristics 2020, 26, 339–352. [Google Scholar] [CrossRef]
  5. Xu, X.; Li, J.; Zhou, M. Delaunay-Triangulation-Based Variable Neighborhood Search to Solve Large-Scale General Colored Traveling Salesman Problems. IEEE Trans. Intell. Transp. Syst. 2021, 22, 1583–1593. [Google Scholar] [CrossRef]
  6. Zhao, K.; Xu, B.L.; Lu, M.L.; Shi, J.; Li, Z. An Efficient Scheduling and Navigation Approach for Warehouse Multi-Mobile Robots. In Proceedings of the 13th International Conference on Swarm Intelligence (ICSI), Xi’an, China, 15–19 July 2022. [Google Scholar] [CrossRef]
  7. Valero-Gomez, A.; Valero-Gomez, J.; Castro-Gonzalez, A.; Moreno, L. Use of genetic algorithms for target distribution and sequencing in multiple robot operations. In Proceedings of the 2011 IEEE International Conference on Robotics and Biomimetics (ROBIO), Phuket, Thailand, 7–11 December 2011; pp. 2718–2724. [Google Scholar] [CrossRef]
  8. Nemoto, K.; Aiyama, Y. Planning Method of Near-Minimum-Time Task Tour for Industrial Point-to-Point Robot. In Proceedings of the 9th IEEE International Conference on Cybernetics and Intelligent Systems (CIS)/IEEE Conference on Robotics, Automation and Mechatronics (RAM), Bangkok, Thailand, 18–20 November 2019. [Google Scholar] [CrossRef]
  9. Seo, J.; Yim, M.; Kumar, V. Assembly sequence planning for constructing planar structures with rectangular modules. In Proceedings of the 2016 IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016. [Google Scholar] [CrossRef]
  10. Yu, J.B.; Liu, G.D.; Xu, J.P.; Zhao, Z.Y.; Chen, Z.H.; Yang, M.; Wang, X.Y.; Bai, Y.T. A Hybrid Multi-Target Path Planning Algorithm for Unmanned Cruise Ship in an Unknown Obstacle Environment. Sensors 2022, 22, 2429. [Google Scholar] [CrossRef]
  11. Xie, X.Y.; Wang, Y.L.; Wu, Y.J.; You, M.; Zhang, S.Y. Random Patrol Path Planning for Unmanned Surface Vehicles in Shallow Waters. In Proceedings of the 19th IEEE International Conference on Mechatronics and Automation (IEEE ICMA), Guilin, China, 7–10 August 2022; pp. 1860–1865. [Google Scholar] [CrossRef]
  12. Faridi, A.Q.; Sharma, S.; Shukla, A.; Tiwari, R.; Dhar, J. Multi-robot multi-target dynamic path planning using artificial bee colony and evolutionary programming in unknown environment. Intell. Serv. Robot. 2018, 11, 171–186. [Google Scholar] [CrossRef]
  13. Gao, Y.; Liu, J.; Hu, M.Q.; Xu, H.; Li, K.P.; Hu, H. A New Path Evaluation Method for Path Planning with Localizability. IEEE Access 2019, 7, 162583–162597. [Google Scholar] [CrossRef]
  14. Zhang, X.H.; Guo, Y.; Yang, J.Q.; Li, D.L.; Wang, Y.; Zhao, R. Many-objective evolutionary algorithm based agricultural mobile robot route planning. Comput. Electron. Agric. 2022, 200, 107274. [Google Scholar] [CrossRef]
  15. Borenstein, J.; Feng, L. UMBmark: A benchmark test for measuring odometry errors in mobile robots. Proc. SPIE—Int. Soc. Opt. Eng. 1995, 2591, 113–124. [Google Scholar] [CrossRef]
  16. Lee, K.; Jung, C.; Chung, W. Accurate calibration of kinematic parameters for two wheel differential mobile robots. J. Mech. Sci. Technol. 2011, 25, 1603. [Google Scholar] [CrossRef]
  17. Doh, N.; Choset, H.; Chung, W.K. Accurate relative localization using odometry. IEEE Int. Conf. Robot. Autom. 2003, 2, 1606–1612. [Google Scholar] [CrossRef]
  18. Doh, N.L.; Choset, H.; Chung, W.K. Relative localization using path odometry information. Auton. Robot. 2006, 21, 143–154. [Google Scholar] [CrossRef]
  19. Carvalho Filho, J.G.N.D.; Carvalho, E.A.N.; Molina, L.; Freire, E.O. The Impact of Parametric Uncertainties on Mobile Robots Velocities and Pose Estimation. IEEE Access 2019, 7, 69070–69086. [Google Scholar] [CrossRef]
  20. Martin, J.; Ansuategi, A.; Maurtua, I.; Gutierrez, A.; Obregón, D.; Casquero, O.; Marcos, M. A Generic ROS-Based Control Architecture for Pest Inspection and Treatment in Greenhouses Using a Mobile Manipulator. IEEE Access 2021, 9, 94981–94995. [Google Scholar] [CrossRef]
  21. Fan, Q.; Gong, Z.; Zhang, S.; Tao, B.; Yin, Z.; Ding, H. A vision-based fast base frame calibration method for coordinated mobile manipulators. Robot. Comput. Integr. Manuf. 2021, 68, 102078. [Google Scholar] [CrossRef]
  22. Wu, Z.; Chen, Y.; Liang, J.; He, B.; Wang, Y. ST-FMT*: A Fast Optimal Global Motion Planning for Mobile Robot. IEEE Trans. Ind. Electron. 2022, 69, 3854–3864. [Google Scholar] [CrossRef]
  23. Qi, J.; Yang, H.; Sun, H. MOD-RRT*: A Sampling-Based Algorithm for Robot Path Planning in Dynamic Environment. IEEE Trans. Ind. Electron. 2020, 68, 7244–7251. [Google Scholar] [CrossRef]
  24. Lo, K.; Yi, W.; Wong, P.; Leung, K.; Leung, Y.; Mak, S. A Genetic Algorithm with New Local Operators for Multiple Traveling Salesman Problems. Int. J. Comput. Intell. Syst. 2018, 11, 692–705. [Google Scholar] [CrossRef] [Green Version]
  25. Jana, R.K.; Mitra, K.K.; Sharma, D.K. Software vendors travel management decisions using an elitist nonhomogeneous genetic algorithm. Int. J. Prod. Econ. 2018, 202, 123–131. [Google Scholar] [CrossRef]
  26. Chen, X.; Gao, P. Path planning and control of soccer robot based on genetic algorithm. J. Ambient Intell. Humaniz. Comput. 2020, 11, 6177–6186. [Google Scholar] [CrossRef]
  27. Zhang, T.; Xu, G.; Zhan, X.; Han, T. A new hybrid algorithm for path planning of mobile robot. J. Supercomput. 2022, 78, 4158–4181. [Google Scholar] [CrossRef]
  28. Dubois, A.; Bresciani, J.P. Validation of an ambient system for the measurement of gait parameters. J. Biomech. 2018, 69, 175–180. [Google Scholar] [CrossRef] [PubMed] [Green Version]
  29. Guo, J.; Zhang, Q.; Chai, H.; Li, Y. Obtaining lower-body Euler angle time series in an accurate way using depth camera relying on Optimized Kinect CNN. Measurement 2022, 188, 110461. [Google Scholar] [CrossRef]
Figure 1. Workspace of the multiple-target path planning problem.
Figure 1. Workspace of the multiple-target path planning problem.
Sensors 23 00517 g001
Figure 2. Structure examples for mobile and motion modes. (a) Moving forward. (b) Rotating in situ.
Figure 2. Structure examples for mobile and motion modes. (a) Moving forward. (b) Rotating in situ.
Sensors 23 00517 g002
Figure 3. The target point distribution and the path solution. (a) Target points placed in the workspace. (b) The optimal path with the shortest length. (c) The optimal path with the least rotation.
Figure 3. The target point distribution and the path solution. (a) Target points placed in the workspace. (b) The optimal path with the shortest length. (c) The optimal path with the least rotation.
Sensors 23 00517 g003
Figure 4. A realistic example of multiple-target position tracking. (a) Ideal positions and actual moving path in experiment. (b) Errors between the ideal positions and actual positions at each target point.
Figure 4. A realistic example of multiple-target position tracking. (a) Ideal positions and actual moving path in experiment. (b) Errors between the ideal positions and actual positions at each target point.
Sensors 23 00517 g004
Figure 5. The rotation center lateral offset caused by the velocity difference.
Figure 5. The rotation center lateral offset caused by the velocity difference.
Sensors 23 00517 g005
Figure 6. The arc-shaped trajectory caused by the rotation center lateral offset.
Figure 6. The arc-shaped trajectory caused by the rotation center lateral offset.
Sensors 23 00517 g006
Figure 7. Position error when moving from one target point to the next one.
Figure 7. Position error when moving from one target point to the next one.
Sensors 23 00517 g007
Figure 8. Prototype of mobile robot and the motion capture system. (a) The four Mecanum wheels of the mobile robot. (b) The overall view of the mobile robot prototype. (c) Marked points on the mobile robot. (d) The rigid triangle formed by marked points that represents the motion of the mobile robot. (e) The geometric principle of the multiple-camera stereo system.
Figure 8. Prototype of mobile robot and the motion capture system. (a) The four Mecanum wheels of the mobile robot. (b) The overall view of the mobile robot prototype. (c) Marked points on the mobile robot. (d) The rigid triangle formed by marked points that represents the motion of the mobile robot. (e) The geometric principle of the multiple-camera stereo system.
Sensors 23 00517 g008
Figure 9. The algorithm principle of stationary segment recognition. (a) The coordinates of the same marked point in time series. (b) The coordinate series in stationary status. (c) The coordinate series in motive status. (d) The coordinate series when the marked point is about to stop. (e) The coordinate series when the marked point is about to move.
Figure 9. The algorithm principle of stationary segment recognition. (a) The coordinates of the same marked point in time series. (b) The coordinate series in stationary status. (c) The coordinate series in motive status. (d) The coordinate series when the marked point is about to stop. (e) The coordinate series when the marked point is about to move.
Sensors 23 00517 g009
Figure 10. Stationary segment recognition.
Figure 10. Stationary segment recognition.
Sensors 23 00517 g010
Figure 11. Arc fitting for forward-moving trajectory.
Figure 11. Arc fitting for forward-moving trajectory.
Sensors 23 00517 g011
Figure 12. The distribution of the error parameter from experiments. (a) The distribution of the forward moving error coefficient. (b) The distribution of the rotation angle error coefficient. (c) The distribution of the fitted trajectory radius.
Figure 12. The distribution of the error parameter from experiments. (a) The distribution of the forward moving error coefficient. (b) The distribution of the rotation angle error coefficient. (c) The distribution of the fitted trajectory radius.
Sensors 23 00517 g012
Figure 13. Destination offset caused by arc-shaped trajectory.
Figure 13. Destination offset caused by arc-shaped trajectory.
Sensors 23 00517 g013
Figure 14. Precision optimal path and the comparison with the characteristic path. (a)The ideal positions and the actual reached positions when the mobile robot moves along the precision-driven optimal path. (b)The distances between the ideal positions and the actual reached positions at each target position when mobile robot moves along three different paths.
Figure 14. Precision optimal path and the comparison with the characteristic path. (a)The ideal positions and the actual reached positions when the mobile robot moves along the precision-driven optimal path. (b)The distances between the ideal positions and the actual reached positions at each target position when mobile robot moves along three different paths.
Sensors 23 00517 g014
Figure 15. Simulated positions with different path and error parameters. (a) The simulated positions for mobile robot moving along the minimum rotation angle path with considering the forward moving error coefficient as a random variable. (b) The simulated positions for mobile robot moving along the minimum average position error path with considering the forward moving error coefficient as a random variable. (c) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering the forward moving error coefficient as a random variable. (d) The simulated positions for mobile robot moving along the minimum rotation angle path with considering the rotation angle error coefficient as a random variable. (e) The simulated positions for mobile robot moving along the minimum average position error path with considering the rotation angle error coefficient as a random variable. (f) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering the rotation angle error coefficient as a random variable. (g) The simulated positions for mobile robot moving along the minimum rotation angle path with considering the rotation center lateral offset as a random variable. (h) The simulated positions for mobile robot moving along the minimum average position error path with considering the rotation center lateral offset as a random variable. (i) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering the rotation center lateral offset as a random variable. (j) The simulated positions for mobile robot moving along the minimum rotation angle path with considering all error parameters are random variables. (k) The simulated positions for mobile robot moving along the minimum average position error path with considering all error parameters are random variables. (l) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering all error parameters are random variables.
Figure 15. Simulated positions with different path and error parameters. (a) The simulated positions for mobile robot moving along the minimum rotation angle path with considering the forward moving error coefficient as a random variable. (b) The simulated positions for mobile robot moving along the minimum average position error path with considering the forward moving error coefficient as a random variable. (c) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering the forward moving error coefficient as a random variable. (d) The simulated positions for mobile robot moving along the minimum rotation angle path with considering the rotation angle error coefficient as a random variable. (e) The simulated positions for mobile robot moving along the minimum average position error path with considering the rotation angle error coefficient as a random variable. (f) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering the rotation angle error coefficient as a random variable. (g) The simulated positions for mobile robot moving along the minimum rotation angle path with considering the rotation center lateral offset as a random variable. (h) The simulated positions for mobile robot moving along the minimum average position error path with considering the rotation center lateral offset as a random variable. (i) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering the rotation center lateral offset as a random variable. (j) The simulated positions for mobile robot moving along the minimum rotation angle path with considering all error parameters are random variables. (k) The simulated positions for mobile robot moving along the minimum average position error path with considering all error parameters are random variables. (l) The simulated positions for mobile robot moving along the minimum forward moving distance path with considering all error parameters are random variables.
Sensors 23 00517 g015
Figure 16. Position scatters of simulated results and experimental results. (a) The simulated and experimental positions for mobile robot moving along the minimum rotation angle path. (b) The simulated and experimental positions for mobile robot moving along the minimum average position error path. (c) The simulated and experimental positions for mobile robot moving along the minimum forward moving distance path.
Figure 16. Position scatters of simulated results and experimental results. (a) The simulated and experimental positions for mobile robot moving along the minimum rotation angle path. (b) The simulated and experimental positions for mobile robot moving along the minimum average position error path. (c) The simulated and experimental positions for mobile robot moving along the minimum forward moving distance path.
Sensors 23 00517 g016
Figure 17. Movement precision experiment with different paths. (a) The simulated and experimental positions for mobile robot moving along the minimum rotation angle path with command compensation. (b) The simulated and experimental positions for mobile robot moving along the minimum average position error path with command compensation. (c) The simulated and experimental positions for mobile robot moving along the minimum forward moving distance path with command compensation.
Figure 17. Movement precision experiment with different paths. (a) The simulated and experimental positions for mobile robot moving along the minimum rotation angle path with command compensation. (b) The simulated and experimental positions for mobile robot moving along the minimum average position error path with command compensation. (c) The simulated and experimental positions for mobile robot moving along the minimum forward moving distance path with command compensation.
Sensors 23 00517 g017
Figure 18. Flowchart for the movement command compensation.
Figure 18. Flowchart for the movement command compensation.
Sensors 23 00517 g018
Table 1. Error parameters estimated by the experiment.
Table 1. Error parameters estimated by the experiment.
Error ParametersMean ValueStandard Deviation
k s 0.9758870.0029193
k r 1.000630.0081595
d r 0.14965 mm0.07293 mm
Table 2. Experimental validation of position error with proposed three-parameter error model (mm).
Table 2. Experimental validation of position error with proposed three-parameter error model (mm).
Path with the Least RotationPath with Optimal PrecisionPath with the Shortest Length
Position
Sequence
Simulated
Error
Average Experimental Error Δ d Position
Sequence
Simulated
Error
Average Experimental Error Δ d Position
Sequence
Simulated
Error
Average Experimental Error Δ d
10.000.00010.000.00010.000.000
25.116.50−1.3925.115.61−0.525.116.40−1.29
313.0415.44−2.4313.0412.840.235.475.280.19
415.2717.36−2.09415.2714.280.9946.516.310.2
524.8729.63−4.76518.8017.431.37513.3415.14−1.8
628.8933.97−5.08624.7124.81−0.1616.3116.90−0.59
724.3529.18−4.83724.0720.983.09720.9322.31−1.38
823.4328.01−4.58828.7126.152.56828.6429.75−1.11
924.5626.45−1.89925.2523.142.11936.7039.27−2.57
1032.9525.207.751032.6132.230.381046.1749.53−3.36
1130.7621.109.661124.8622.692.171141.3543.77−2.42
1218.1214.133.991228.6730.82−2.151227.8833.75−5.87
1371.1355.9715.161310.8117.29−6.481325.4233.21−7.79
1454.4940.2814.211415.6021.90−6.31430.2136.54−6.33
1525.9516.849.111519.5523.55−41537.2943.12−5.83
1625.7917.807.991643.5944.53−0.941654.9863.50−8.52
1726.4719.876.61740.2937.922.371755.9962.16−6.17
1827.6526.840.811825.2721.663.611862.9070.22−7.32
1929.9131.02−1.111927.2321.206.031978.5288.09−9.57
2032.2936.18−3.892030.1420.569.582067.9572.71−4.76
2189.8890.25−0.372118.0711.986.092172.4578.00−5.55
22126.41124.062.352298.7482.3616.382297.97109.08−11.11
Table 3. Average position error of simulation and experiment (mm).
Table 3. Average position error of simulation and experiment (mm).
Type of PathAverage Error of Simulated PositionsAverage Error of Experimental Positions
Minimum rotation angle path37.12 mm32.09 mm
Minimum theoretical error path27.42 mm24.27 mm
Minimum forward moving distance path43.82 mm42.05 mm
Table 4. Average position error at each target position (mm).
Table 4. Average position error at each target position (mm).
Position
Sequence
Path with the Least RotationPath with Optimal PrecisionPath with the Shortest Length
10.000.000.00
22.402.362.25
36.235.913.89
47.356.754.59
510.607.517.22
612.558.418.48
712.448.749.64
812.1810.1211.95
912.529.9013.98
108.7411.2516.19
119.2710.1515.01
128.9110.058.83
1321.348.598.47
1419.548.867.98
1513.458.929.66
1611.7412.3913.49
1710.7413.4514.17
188.3014.2816.10
198.0714.9019.26
208.8516.1218.28
2113.7016.0919.41
2217.5122.1923.43
Table 5. Average error of simulation and experiment (mm).
Table 5. Average error of simulation and experiment (mm).
Type of PathAverage Error of Simulated PositionsAverage Error of Experimental Positions
Minimum rotation angle path13.36 mm10.75 mm
Minimum theoretical error path11.34 mm10.32 mm
Minimum forward moving distance path15.64 mm11.47 mm
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Ji, J.; Zhao, J.-S.; Misyurin, S.Y.; Martins, D. Precision-Driven Multi-Target Path Planning and Fine Position Error Estimation on a Dual-Movement-Mode Mobile Robot Using a Three-Parameter Error Model. Sensors 2023, 23, 517. https://doi.org/10.3390/s23010517

AMA Style

Ji J, Zhao J-S, Misyurin SY, Martins D. Precision-Driven Multi-Target Path Planning and Fine Position Error Estimation on a Dual-Movement-Mode Mobile Robot Using a Three-Parameter Error Model. Sensors. 2023; 23(1):517. https://doi.org/10.3390/s23010517

Chicago/Turabian Style

Ji, Junjie, Jing-Shan Zhao, Sergey Yurievich Misyurin, and Daniel Martins. 2023. "Precision-Driven Multi-Target Path Planning and Fine Position Error Estimation on a Dual-Movement-Mode Mobile Robot Using a Three-Parameter Error Model" Sensors 23, no. 1: 517. https://doi.org/10.3390/s23010517

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