Control of Velocity-Constrained Stepper Motor-Driven Hilare Robot for Waypoint Navigation

Robins Mathew , Somashekhar S. Hiremath

Engineering ›› 2018, Vol. 4 ›› Issue (4) : 491 -499.

PDF (1659KB)
Engineering ›› 2018, Vol. 4 ›› Issue (4) :491 -499. DOI: 10.1016/j.eng.2018.07.013
Research
Research Robotics—Article
Control of Velocity-Constrained Stepper Motor-Driven Hilare Robot for Waypoint Navigation
Author information +
History +
PDF (1659KB)

Abstract

Finding an optimal trajectory from an initial point to a final point through closely packed obstacles, and controlling a Hilare robot through this trajectory, are challenging tasks. To serve this purpose, path planners and trajectory-tracking controllers are usually included in a control loop. This paper highlights the implementation of a trajectory-tracking controller on a stepper motor-driven Hilare robot, with a trajectory that is described as a set of waypoints. The controller was designed to handle discrete waypoints with directional discontinuity and to consider different constraints on the actuator velocity. The control parameters were tuned with the help of multi-objective particle swarm optimization to minimize the average cross-track error and average linear velocity error of the mobile robot when tracking a predefined trajectory. Experiments were conducted to control the mobile robot from a start position to a destination position along a trajectory described by the waypoints. Experimental results for tracking the trajectory generated by a path planner and the trajectory specified by a user are also demonstrated. Experiments conducted on the mobile robot validate the effectiveness of the proposed strategy for tracking different types of trajectories.

Keywords

Trajectory tracking / Adaptive control / Waypoint navigation / Hilare robot / Particle swarm optimization / Probabilistic road map

Cite this article

Download citation ▾
Robins Mathew, Somashekhar S. Hiremath. Control of Velocity-Constrained Stepper Motor-Driven Hilare Robot for Waypoint Navigation. Engineering, 2018, 4(4): 491-499 DOI:10.1016/j.eng.2018.07.013

登录浏览全文

4963

注册一个新账户 忘记密码

1. Introduction

The application of mobile robots, and particularly wheeled mobile robots (WMRs), is exponentially increasing in today’s fast-growing market. These robots play a major role in many sectors, with their applications ranging from service robots to military robots. The Hilare robot is one type of robot among WMRs with a number of applications, primarily in indoor environments. Fig. 1 provides a schematic diagram of a Hilare robot. This type of mobile robot has two independently actuated wheels mounted on either side of the body in such a way that the central axis of wheels coincides with each other, and has one or more passive wheels to balance the robot [1]. The ease of design, ease of manufacturing, and ease of predicting the dynamics for this type of mobile robot make it a simple, suitable, and economic choice among the different ground contact mobile robots that are currently available [2].

The motion of a Hilare robot is controlled by controlling the velocities of the independent right and left wheels. When the wheels roll on the contact surface without lateral slip, non-holonomic behavior is induced in the robot motion. In the inverse kinematics of the mobile robot, this non-holonomic behavior appears as a constraint on the robot velocity that cannot be transformed into a position constraint [3]. Although the robot cannot move sideways, it can reach any desired position and orientation in the workspace by taking a complex trajectory. Since the robot cannot move sideways, finding an optimal trajectory from an initial point to a final point through closely packed obstacles, and controlling the robot through this trajectory, are challenging tasks. To serve this purpose, path planners and trajectory-tracking controllers are usually included in a control loop. The same tasks would be much easier if the mobile robot had the ability to move sideways.

A trajectory-tracking controller is the lowest level in a layered control architecture, and is essential for the motion control of any mobile robot. The main objective of the trajectory-tracking controller is to reduce the cross-track error [4]. Over the years, many approaches have been developed for the control of the Hilare robot [5]. The simplest approach to control the motion of this mobile robot is to use motion primitives, such as straight motion and in-place turning. A suitable combination of these primitives is used to control the robot through the predefined trajectory [6,7]. However, this strategy may cause unwanted jerks and oscillations that affect the smoothness of the motion and the stability. Research on path-tracking controllers for a car-like robot [8] has shown that the stability of the controller is affected also by look-ahead distance. That work also suggests that a large look-ahead distance will result in cutting corners. According to the literature, other control methods such as adaptive control, the back-stepping method, artificial neural networks, fuzzy control, biologically inspired methods, potential field-based control, and so forth have been evolved over time for the smooth and stable tracking control of mobile robots [911]. Of these methods, a well-established method to control a mobile robot is a stable tracking controller, as proposed by Kanayama et al. [12]. This method is applicable to all types of autonomous mobile robots. The controller works such that the position and orientation error of the mobile robot with respect to a reference trajectory is reduced. The literature shows that this method can be modified further to develop smooth tracking controllers [1315].

A reference trajectory for the controller can be obtained from the operator or from a path-planning algorithm. In general, path planning comes before the trajectory-tracking controller in the control hierarchy, and is very important in mobile robot navigation. Different approaches have been proposed, with different levels of complexity, accuracy, and applicability, for planning a feasible path for mobile robots [16]. Geometric path-planning algorithms [17], rapidly-exploring random trees (RRTs) [18], and probabilistic road maps (PRMs) [19] are some of the algorithms that can provide a reference trajectory to the tracking controller. A PRM is a well-known technique for planning an admissible path for a non-holonomic mobile robot. A PRM-based path planner can find the trajectory that must be followed by the mobile robot in order to reach the destination and to avoid the various obstacles.

Although many control methods have been developed for trajectory-tracking control, few efforts have been made to study a controller that is implemented in a layered control architecture in which the output of a path planner acts as an input to the controller. The available literature also lacks an explanation of the implementation of these controllers in Hilare robots with stepper motor-driven wheels. The current paper focuses on addressing these gaps in the literature. We propose a control strategy that can guide a mobile robot along a reference trajectory that is specified as a set of discontinuous waypoints through which the mobile robot must move in order to reach the destination. Parameter optimization has been carried out to minimize the average cross-track error and average linear velocity error of the mobile robot.

The paper is organized as follows: Section 2 presents the kinematic model and controller design; Section 3 presents the simulation and optimization of control parameters; experimentation is presented in Section 4; and conclusions and future work are detailed in Section 5.

2. Kinematic model and controller design

Consider a Hilare robot, as shown in Fig. 2, located on a two-dimensional surface for which a global coordinate system (inertial frame (XI, YI)) is defined. The robot has three degrees of freedom on the surface. The posture (Pi) of the mobile robot at any given instant i constitutes the position (xi, yi) of the mobile robot and its heading angle (θi) (Eq. (1)). Here xi and yi are the inertial frame intercepts of the center of the axis connecting the actuated wheels. The direction perpendicular to the axis connecting the center of the actuated wheels is considered to be the heading direction of the mobile robot—that is, the X axis of the local frame connected to the mobile robot. The heading angle (θi) of the mobile robot is the angle between the XI axis of the inertial frame and X axis of the local frame. Thus, in further calculations, the mobile robot is assumed to be a point body located at the center of the axis connecting the actuated wheels. The locus of the points (xi, yi) over time is considered to be the trajectory being tracked by the mobile robot.

Pi=xiyiθi

In the present study, the trajectory to be tracked by the mobile robot is specified as a path connecting the waypoints from a start position (Pw0 (xw0, yw0)) to a destination position (Pwn (xwn, ywn)) through a set of discontinuous waypoints (Pwk (xwk, ywk)). Here, k is an integer between zero and the total number of waypoints (n) and w stands for waypoint. The linear and angular velocities of the mobile robot are given by vi and ωi, respectively. The rate of change in the posture (Ṗi) of the mobile robot with respect to the linear velocity (vi) and angular velocity (ωi) of the robot can be resolved into the horizontal velocity component (ẋi), vertical velocity component (ẏi), and angular velocity components (θ̇i) (Eq. (2)).

Ṗi=ẋiẏiθ̇i=cosθi0sinθi001viωi

To calculate the linear velocity and angular velocity, the right and the left wheels of the mobile robot are considered to be rotating at angular velocities of ω1i and ω2i, respectively. The linear velocity of the mobile robot due to the rotation of these wheels can be calculated by combining the individual wheel velocities, as shown in Fig. 3(a); the angular velocity can be calculated as shown in Fig. 3(b).

The linear velocity vi and the angular velocity ωi of the mobile robot due to the rotation of the wheels is given in Eq. (3). Here, wT is the width of the wheel track and dw is the wheel diameter. To calculate these velocities, it is assumed that the wheels roll on the surface without slipping, and that these actuated wheels have the same diameter.

viωi=14dwdw2dwwT-2dwwTω1iω2i

Eq. (4) can be obtained by taking the inverse transformation of Eq. (3). This equation describes the transformation of the velocities (vi, ωi) of the mobile robot into the wheel angular velocities (ω1i, ω2i).

ω1iω2i=1dw2wT2-wTviωi

The posture error (Pei = [xei, yei, θei]T) of the mobile robot can be found by transforming the global posture error of the mobile robot into the local coordinates (X, Y) of the mobile robot, as shown in Eq. (5). The global posture error is calculated with respect to the inertial frame (XI, YI). Here, [xwk, ywk, θwk]T is the required waypoint posture in the global coordinates.

Pei=xeiyeiθei=cosθisinθi0-sinθicosθi0001xwk-xiywk-yiθwk-θi

θwk is calculated as follows:

θwk=tan-1ywk-yixwk-xi

A kinematic controller is employed to reduce this posture error, and thus control the robot through the desired trajectory. The stable tracking controller proposed by Kanayama et al. [12] is utilized to control the mobile robot such that the posture error will converge to zero. This control law is given by Eq. (7), in which vci and ωci are the control velocities, vri and ωri are the reference velocities of the mobile robot, and k1, k2, and k3 are the control gains.

vciωci=vricosθei+k1xeiωri+k2vriyei+k3vrisinθei

The reference waypoint of the controller should be updated based on the instantaneous posture of the mobile robot so that the mobile robot can be controlled through the trajectory-connecting waypoints. A waypoint update function is applied in the present work in order to calculate the Euclidean distance from the current position of the mobile robot to the reference position. If this distance is within an accepted transition distance dT, the reference posture will be updated and the next waypoint posture will be selected as the new reference posture. Hence, the accepted transition area will be a circle of fixed radius dT around the reference posture. If the robot reaches any point within this circle, then the reference posture will be updated. The constraint on this transition is given by Eq. (8). The distance dT works in a similar way to the look-ahead distance [8] mentioned in the previous section; hence, the selection of dT is critical. With consideration to cutting corners and making wide turns, the dT selected in the present work is 27 mm, which is half of the wheel track width.

xei2+yei2dT

The architecture of the waypoint tracking controller is shown in Fig. 4. It consists of a waypoint planner, which provides a set of waypoints from Pw0 to Pwn that make up the reference trajectory. The waypoint selector module selects the reference waypoint from this set. The waypoint selector takes the waypoint Pw1 as the first reference point; later, it updates the waypoint when the criterion given in Eq. (8) is satisfied. The error estimation block uses Eq. (5) to generate the posture error. The controller uses this posture error and reference velocity to generate the control velocities vci and ωci, as given in Eq. (7). The next module takes care of the input constraints and calculates the wheel velocities corresponding to the control velocities. The step command generator produces the trigger to control the stepper motor. The new posture of the mobile robot is calculated by the posture estimation module. Output of this module acts as feedback. A flow chart of the control algorithm is provided in Appendix A.

The output of the controller module cannot be applied directly to a real robot. The magnitudes of the control velocities will be very large because of the discontinuities in the reference path. Various constraints on the motor may restrict high-magnitude control velocities being implemented on a real mobile robot. These constraints are referred to as “input constraints.” Examples of input constraints include the maximum attainable angular velocity of the driving motor, and user-defined restrictions on the maximum linear and angular velocities of the mobile robot. Fig. 5 shows the different input constraints applied to the velocity space of a forward-moving Hilare robot. To satisfy these input constraints, the control output (Eq. (7)) must be modified. The user-defined restrictions on the linear velocity, vmax and vmin, of the mobile robot can be introduced into the controller by modifying the control velocity vci using Eqs. (9) and (10), respectively. Here, vim1 and vim2 are the modified control velocities.

vim1=αvmax,vci·vci-vmax+vmax

vim2=αvci,vmin·vci-vmin+vmin

where α is a condition parameter , which is defined by Eq. (11).

αm,n=0,mn1,m>n

where m and n can be any arbitrary value.

Similarly, the user-defined restrictions on the angular velocity of the mobile robot, ωmax and ωmin, can be introduced into the controller by modifying the control velocity ωci, as shown in Eqs. (12) and (13), respectively. Here, ωim1 and ωim2 are modified control velocities.

ωim1=γωci·αωmax,ωci·ωci-ωmax+ωmax

ωim2=γω·αωci,ωmin·ωci-ωmin+ωmin

where γ(ω) is a condition parameter for the angular velocity, which is given by Eq. (14):

γω=-1,ω<01,ω0

Eq. (15) is obtained by combining Eqs. (9) and (10). Here, vim indicates the modified linear velocity.

vim=αvmax,vci·vci-vmax+vmax+αvci,vmin·vci-vmin+vmin-vci

Similarly, Eq. (16) is obtained by combining Eqs. (12) and (13). Here, ωim indicates the modified angular velocity.

ωim=γ(ωci)·αωmax,ωci·ωci-ωmax+ωmax+αωci,ωmin·ωci-ωmin+ωmin-ωci

The maximum possible linear velocity (a) can be calculated as shown in Eq. (17), by assuming that both motors have the same properties and both wheels are of the same dimension. Here, ω1max and ω2max are the maximum possible angular velocities of the right and left motors, respectively.

a=dw·ω1max2=dw·ω2max2

The constraints on the linear velocity and on the angular velocity of the mobile robot due to this upper limit on the angular velocity of the motor can be found by combining Eqs. (17) and (4), as shown below, and by replacing ω1 and ω2 with ω1max and ω2max in Eq. (4).

ω1maxω2max1dw2wT2-wTviωi

dw2ω1maxdw2ω2maxvi+ωiwT2vi-ωiwT2

aavi+ωiwT2vi-ωiwT2

avi+ωiwT2andavi-ωiwT2

Considering that ωi in the above equations can be positive or negative, the constraint on the linear velocity and on the angular velocity is given by Eq. (22).

vi+wTωi2a

The linear velocity and angular velocity calculated in Eqs. (15) and (16) are further modified, as shown in Eqs. (23) and (24), to satisfy the restrictions on the maximum attainable angular velocity of the driving motor, and thus to generate the final control velocities. These control velocities can be implemented on an actual mobile robot. Eqs. (23) and (24) are implemented in the wheel velocity module of the control loop.

vi=αvim+wTωim2,a·vim·avim+wTωim2-vmax+vim

ωi=γωimαvim+wTωim2,a·ωim·avim+wTωim2-ωim+ωim

To apply the calculated control velocities and execute the control action, the control velocities must be transformed into the corresponding motor control input. In the current scenario, the wheels of the mobile robot are actuated by a stepper motor. The control signal to the stepper motor is usually generated with the help of a timer module. The timer count c used in the timer provides the necessary delay between each step. This time delay Δt is given in Eq. (25), where f is the frequency of the timer.

Δt=cf

The linear velocity and angular velocity of the mobile robot, which are calculated in Eqs. (23) and (24), are applied in Eq. (4) in order to obtain the angular velocities ω1i and ω2i at which the right and left motors must rotate. Angles Δθ1i and Δθ2i, which should be moved by each motor within the given time interval in order to achieve the required linear velocity and angular velocity of the mobile robot, can be found by multiplying the angular velocity of the wheel with the time interval, as shown in Eq. (26). Here, Tlag is the time lag that may occur in calculating the required wheel velocity.

Δθ1iΔθ2i=ω1iω2i·Tlag

However, the stepper motor can only move by a fixed angle (β) in each step. This imposes restrictions on the wheel rotation; that is, the wheels should rotate only if the required angle of rotation is greater than β. To satisfy this restriction and to obtain smooth motion without the effect of Tlag, the motor step command (i.e., motion command) is generated with the help of a timer interrupt-driven subroutine, as shown in Fig. 4, while the wheel velocity calculation runs in the main control loop. This allows the robot to move and update the posture (i.e., execute the previously calculated velocity commands) while calculating the required wheel velocity commands for the next instance. The timer is kept such that it will operate at the maximum step frequency of the stepper motor, which is 1 kHz in the present study. In the subroutine, the calculated values of Δθ1i and Δθ2i are added, respectively, to the unmoved angles θ1(i−1) and θ2(i−1) that were calculated in the previous cycle of the subroutine. If the sum calculated using Eq. (27) is larger than β, then stepper motor triggering occurs. This triggering criterion is provided in Eq. (28), where T1i and T2i are the triggering signals of the right and left motors, respectively. This timer-driven motor step command generation ensures real-time control of the robot.

θ1θ2=θ1(i-1)θ2(i-1)+Δθ1iΔθ2i

T1i=1,θ1β0,otherwiseandT2i=1,θ2β0,otherwise

After generating the signals to the motors, the value of the unmoved angle is updated, as shown in Eq. (29):

θ1iθ2i=θ1θ2-T1i·βT2i·β

Eqs. (26)–(29) are implemented in the step command generator module of the control loop. The actual angular velocity of the motor is calculated using Eq. (30):

ω1iω2i=1ΔtT1i·βT2i·β

The new posture Pi+1 of the mobile robot, as given in Eq. (31), is obtained by combining Eqs. (1) and (2). Here, the rate of change of the posture is obtained by applying Eq. (30) in Eq. (3), in order to obtain the actual velocities vi and ωi of the mobile robot in the given time interval, and then substituting the linear and angular velocities into Eq. (2).

Pi+1=xi+1yi+1θi+1=xiyiθi+ẋiẏiθ̇i·Δt

This equation is implemented in the posture estimation module of the controller in order to find the instantaneous posture of the mobile robot.

3. Simulation and optimization of control parameters

The multi-objective particle swarm optimization (MOPSO) technique [20] was performed to select the control parameters, such as the control gains (k1, k2, k3) and the maximum linear and angular velocity limits (vmax, ωmax) of the proposed controller, so that the tracking errors would be minimal. The objectives of the optimization were to minimize the average cross-track error and the average linear velocity error of the mobile robot, while tracking a step-shaped trajectory using the controller mentioned in the previous section. The cross-track error was calculated as the distance from the mobile robot to the line connecting the current waypoint with the previous waypoint. The linear velocity error is the difference between the measured velocity and the reference velocity (vri). The optimization was carried out based on the simulation results. In this simulation, these errors were calculated by simulating the trajectory that will be tracked by the mobile robot when the proposed controller is used. The parameters used for the simulation are listed in Table 1. These parameters were selected based on the specifications of a commercially available research platform e-puck robot, on which the experiments were carried out. The MOPSO algorithm performed 20 000 evaluations to produce local Pareto front of 50 particles. Each evaluation consisted of simulating the trajectory tracked by the mobile robot for a particular set of control parameters selected by MOPSO. The range within which the control parameters were optimized is given in Table 2.

Fig. 6 shows the Pareto front produced with the help of the MOPSO for the objective functions. To produce this Pareto front, the MOPSO utilized the average linear velocity error and the average cross-track error calculated in the simulation. Each point on the Pareto front represents a set of optimal parameters. The reference step-shaped trajectory and the simulated trajectory for an optimized parameter set (k1 = 0.0247, k2 = 2.9671, k3 = 0.552, vmax = 41 mm·s−1, ωmax = 0.747 rad·s−1) selected from the Pareto front is shown in Fig. 7. The point on the Pareto front corresponding to this set is marked as (A) in Fig. 6.

Fig. 8 shows the linear velocity of the mobile robot while tracking the step-shaped trajectory during the simulation. The average cross-track error and the average linear velocity error obtained from this simulation were 2.63 mm and 2.62 mm·s−1, respectively. These errors were calculated by taking the average of the error produced in each iteration during the simulation.

4. Experimentation

4.1. Experimental setup

Fig. 9 shows the experimental setup, which consists of a mobile robot in an indoor environment on top of a smooth platform that was developed for the experiments. A vision-based measurement system placed over the platform was utilized to analyze the motion of the mobile robot. This system measures the linear velocity of the mobile robot as well as the locus of the points through which the mobile robot moved. The velocity of the mobile robot was limited by user-defined restrictions: vmax = 41 mm·s−1, vmin = 0 mm·s−1, ωmin = 0 rad·s−1, and ωmax = 0.747 rad·s−1. The selected control gains for the experiment were k1 = 0.0247, k2 = 2.9671, and k3 = 0.552. The point corresponding to this combination of control gains was selected from the Pareto front by giving proper weightage to the average cross-track error and average linear velocity error. The maximum velocity limits and control gains were selected based on the optimization results explained in the previous section. The mobile robot uses the motor step count as a feedback signal. The control cycle consists of two parts—the control loop and a timer interrupt subroutine—which was implemented in a dsPIC30F6014A microcontroller system. The main control loop calculates the required wheel velocity, based on the control strategy developed in Section 2. The interrupt subroutine generates the control command to the motors to rotate (step command generator module in Fig. 4) and calculates the new posture of the mobile robot (position estimation module in Fig. 4). The control cycle was 5 ms, but the control signal to the motor was produced every millisecond with the help of the timer interrupt (Tlag = 5 ms, Δt = 1 ms). This strategy allows the mobile robot to move smoothly, without any jerks occurring due to lag in the motor control signal. Since the motor control commands are generated every millisecond, the mobile robot can be instructed to move at a linear velocity of 130 mm·s−1, which is equal to 1000 steps·s−1.

The mobile robot was initially placed on the platform at a known location and orientation (x0, y0, θ0) = (200 mm, 200 mm, 0 rad). It was connected wirelessly to a computer, and the reference trajectory to be tracked was communicated to the mobile robot through this connection. These reference trajectories were communicated as a set of waypoints that connect to form the trajectory. During the experiment, video of the mobile robot motion over the platform was captured using the vision-based measurement system. This video was post-processed to obtain the actual linear velocity of the mobile robot and the trajectory tracked by the mobile robot. These measurements were then compared with the reference linear velocity and trajectory to determine the effectiveness of the controller in tracking different trajectories. Self-localization of the robot was carried out with the help of the posture estimation module in the control loop, as defined in Eq. (31) in Section 2.

4.2. Experimental results

Experiments were carried out to track three different trajectories: namely, a trajectory generated by a path planner, a rectangular trajectory, and a trajectory that resembles cursive script in English. These trajectories were selected based on the different applications this mobile robot may be used for (i.e., transportation, manufacturing, human assistance). Fig. 9 shows the experimental setup, with obstacles placed on the experimental platform. This particular configuration was used to carry out experiments to track the path-planner-generated trajectory. In the other two experiments, these obstacles were not present.

4.2.1. Path-planner-generated trajectory

In a fully autonomous system, the path planner provides the path that should be tracked by the mobile robot. Thus, in this experiment, the mobile robot was controlled from a start position (200, 200) to a destination position (700, 1400) and avoided obstacles through a trajectory described by a set of waypoints generated by a path planner. The PRM-based path planner implemented in the computer connected to the mobile robot was utilized to generate the waypoints. The locations of the obstacles were manually fed to the PRM to generate the waypoints. The algorithm provides a set of waypoints that describe the reference trajectory. The waypoints were then communicated to the robot using the wireless connection mentioned earlier in this section.

Fig. 10(a) and (b) shows the trajectory tracked by the mobile robot and the linear velocity error, respectively. The average cross-track error during the experiment was found to be 12.88 mm, and the average linear velocity error was found to be 1.24 mm·s−1. The average linear velocity error was minimal when compared with the other trajectory-tracking experiments explained in this paper. This was due to the closeness of the waypoints to each other and to a lower number of sharp turns in the path. Sharp turns are difficult for the mobile robot to follow, due to angular velocity constraints.

4.2.2. Rectangular trajectory

A rectangle with 400 mm of length and 300 mm of width was tracked using the developed controller. The corner points of the rectangle, at (200, 200), (600, 200), (600, 500), and (200, 500), were selected as the waypoints. These waypoints were manually selected and passed to the robot through a wirelessly connected computer. Fig. 11(a) shows the trajectory tracked by the mobile robot and Fig. 11(b) shows the linear velocity error while tracking the rectangular trajectory. The average cross-track error during the experiment was found to be 6.75 mm, and the average linear velocity error was found to be 2.91 mm·s−1.

4.2.3. Cursive script trajectory

An attempt was made to track a complex trajectory that resembles cursive script in English. The waypoints in the trajectory were generated through a user interface: A human operator used a mouse to mark the waypoints corresponding to the text/path to be followed by the mobile robot. An algorithm linked with the user interface selected these waypoints and communicated them to the mobile robot. The user interface was implemented on the computer that was wirelessly connected to the robot. The text selected in this case was the word “So.” This particular word was selected because it provides a trajectory with no isolated points, and can be tracked by the forward motion of the mobile robot. Fig. 12(a) shows the trajectory tracked by the mobile robot and Fig. 12(b) shows the linear velocity error while tracking the trajectory of the cursive script. The average cross-track error was found to be 9.45 mm and the average linear velocity error was found to be 2.46 mm·s−1.

Table 3 provides a summary of the results. The results show that the average cross-track error was highest for the path-planner-generated trajectory (12.88 mm) and lowest for the rectangular trajectory (6.75 mm). This finding contradicts the simulation results. The main reason for the differences between the simulation results and the experimental results is that a wheel slip occurred in the experiment that was not accounted for in the model. Uncertainty in the start position and in the orientation of the mobile robot when it was placed on the experiment platform also contributed to these differences. The average linear velocity error was lowest (1.24 mm·s−1) for the path-planner-generated trajectory and highest for the rectangular trajectory (2.91 mm·s−1). The linear velocity errors predicted in the simulation closely matched those of the experiments. Although there was a mismatch between the predicted and actual cross-track error, the errors were small when compared with the specified trajectory, so the controller was reliable.

5. Conclusions

This paper addressed the control of a stepper motor-driven Hilare robot to track trajectories described by a set of waypoints, and explained the implementation of the controller on an actual mobile robot. The conclusions are as follows:

(1) The major contribution of this work is that it extends the adaptive control strategy to account for directional discontinuities and velocity constraints when controlling a stepper motor-driven mobile robot.

(2) The average cross-track error and the average linear velocity error were reduced by optimizing the control parameters.

(3) The average cross-track error was found to be 12.88 mm for the path-planner-generated trajectory, 6.75 mm for the rectangular trajectory, and 9.45 mm for the cursive script trajectory.

(4) The average linear velocity error was found to be less than 3 mm·s−1 for all the trajectories. This experimental result implies that the proposed method is robust and reliable in tracking different types of trajectories.

(5) The future work is toward reducing the cross-track error and to integrate localization module to avoid error in self localization.

Compliance with ethics guidelines

Robins Mathew and Somashekhar S. Hiremath declare that they have no conflict of interest or financial conflicts to disclose.

References

[1]

Dudek G., Jenkin M.. Computational principles of mobile robotics. 2nd ed.

[2]

Konduri S., Torres E.O.C., Prabhakar R.. Dynamics and control of a differential drive robot with wheel slip: application to coordination of multiple robots. J Dyn Syst Meas Control. 2017; 139(1): 014505.

[3]

Fahimi F.. Autonomous robots: modeling, path planning, and control.

[4]

da Silva J., de Sousa J.. A dynamic programming based path-following controller for autonomous vehicles. Contr Intell Syst. 2011; 39(4): 245-253.

[5]

Kolmanovsky I., McClamroch N.H.. Developments in nonholonomic control problems. IEEE Control Syst. 1995; 15(6): 20-36.

[6]

Nagy Á, Csorvási G, Kiss D. Path planning and control of differential and car-like robots in narrow environments. In: Proceedings of the 13th International Symposium on Applied Machine Intelligence and Informatics; 2015 Jan 22–24; Herl’any, Slovakia; 2015. p. 103–8.

[7]

Mathew R., Hiremath S.S.. Trajectory tracking and control of differential drive robot for predefined regular geometrical path. Procedia Technol. 2016; 25: 1273-1280.

[8]

Snider J.M.. Automatic steering methods for autonomous automobile path tracking.

[9]

Park B., Yoo S.J., Park J.B., Choi Y.H.. A simple adaptive control approach for trajectory tracking of electrically driven nonholonomic mobile robots. IEEE Trans Contr Syst Technol. 2010; 18(5): 1199-1206.

[10]

Valbuena L., Tanner H.G.. Hybrid potential field based control of differential drive mobile robots. J Intell Robot Syst Theory Appl. 2012; 68(3–4): 307-322.

[11]

Chen X., Jia Y., Matsuno F.. Tracking control for differential-drive mobile robots with diamond-shaped input constraints. IEEE Trans Contr Syst Technol. 2014; 22(5): 1999-2006.

[12]

Kanayama Y, Kimura Y, Miyazaki F, Noguchi T. A stable tracking control method for an autonomous mobile robot. In: Proceedings of IEEE International Conference on Robotics and Automation; 1990 May 13–18; Cincinnati, OH, USA. New York: IEEE; 1990. p. 384–9.

[13]

Fukao T., Nakagawa H., Adachi N.. Adaptive tracking control of a nonholonomic mobile robot. IEEE Trans Automat Contr. 2000; 16(5): 609-615.

[14]

Maalouf E., Saad M., Saliah H.. A higher level path tracking controller for a four-wheel differentially steered mobile robot. Robot Auton Syst. 2006; 54(1): 23-33.

[15]

Guo J., Lin Z., Cao M., Yan G.. Adaptive control schemes for mobile robot formations with triangularised structures. IET Control Theory Appl. 2010; 4(9): 1817-1827.

[16]

Miao Y., Khamis A.M., Karray F., Kame M.S.. A novel approach to path planning for autonomous mobile robots. Contr Intell Syst. 2011; 39(4): 235-244.

[17]

Laumond J.P., Jacobs P.E., Taix M., Murray R.M.. A motion planner for nonholonomic mobile robots. IEEE Trans Robot Autom. 1994; 10(5): 577-593.

[18]

In: editor. Rapidly-exploring random trees: a new tool for path planning. Whitefish: Betascript Publishing; 1998.

[19]

Kavraki L., Svestka P., Latombe J.C., Overmars M.H.. Probabilistic roadmaps for path planning in high-dimensional configuration spaces. IEEE Trans Robot Autom. 1996; 12(4): 566-580.

[20]

Coello Coello CA, Leehuga MS. MOPSO: a proposal for multiple objective particle swarm optimization. In: Proceedings of the 2002 Congress on Evolutionary Computation; 2002 May 12–17; Honolulu, HI, USA; 2002. p. 1051–56.

Funding

()

PDF (1659KB)

Supplementary files

Supplementary Material

3637

Accesses

0

Citation

Detail

Sections
Recommended

/