Next Article in Journal
Application of Augmented Reality and Robotic Technology in Broadcasting: A Survey
Previous Article in Journal
Perception-Link Behavior Model: Supporting a Novel Operator Interface for a Customizable Anthropomorphic Telepresence Robot
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Trajectory Planning and Tracking Control of a Differential-Drive Mobile Robot in a Picture Drawing Application

Department of Electrical Engineering, National Taiwan University of Science and Technology, Taipei 10607, Taiwan
*
Author to whom correspondence should be addressed.
Robotics 2017, 6(3), 17; https://doi.org/10.3390/robotics6030017
Submission received: 21 June 2017 / Revised: 7 August 2017 / Accepted: 7 August 2017 / Published: 10 August 2017

Abstract

:
This paper proposes a method for trajectory planning and control of a mobile robot for application in picture drawing from images. The robot is an accurate differential drive mobile robot platform controlled by a field-programmable-gate-array (FPGA) controller. By not locating the tip of the pen at the middle between two wheels, we are able to construct an omnidirectional mobile platform, thus implementing a simple and effective trajectory control method. The reference trajectories are generated based on line simplification and B-spline approximation of digitized input curves obtained from Canny’s edge-detection algorithm on a gray image. Experimental results for image picture drawing show the advantage of this proposed method.

1. Introduction

Wheeled mobile robots are increasingly present in industrial, service, and educational robotics, particularly when autonomous motion capabilities are required on a smooth ground plane. For instance, [1] used image processing techniques to detect, follow, and semi-automatically repaint a half-faded lane mark on an asphalt road. Employing a mobile robot platform in drawing robot applications has the advantages of small size, large work space, portability, and low cost. A drawing robot is a robot that makes use of image processing techniques in input an image and draws the same image picture. A transitional x-y plotter has limits in terms of work space and becomes more expensive for large work sizes. Most portrait drawing robots/humanoid robots make use of multi-degrees of freedom for robot arms [2,3,4,5]. However, it may be too costly to use a robot arm in drawing a picture or portrait.
The basic motion tasks for a mobile robot in an obstacle-free work space are point-to-point motion and trajectory following. Trajectory tracking control is particularly useful in art drawing applications, in which a representative physical point (pen tip, for instance) on the mobile robot must follow a trajectory in the Cartesian space starting from an arbitrary initial posture. The trajectory tracking problem has been solved by various approaches, such as Lyapunov-based non-linear feedback control, dynamic feedback linearization, feed-forward plus feedback control, and others [6,7,8]. In this work, we propose a simple and effective trajectory control method for a picture drawing robot that is based on inverse kinematics and proportional feedback control in discrete time.
Omnidirectional motion capability is another important factor in fine and precise motion applications. Designing a mobile robot with isotropy kinematic characteristics requires three active wheels with a special wheel mechanism design [9]. Kinematic isotropy means the Jacobian matrix is isotropic for all robot poses, which is one of the key factors in robotic mechanism design [10,11]. Kinematic isotropy makes the best use of control degrees of freedom in Cartesian motion.
The standard construction of a mobile drawing robot is based on a classical differential drive chassis with the single castor in the back of the robot [12,13]. Some robots are driven by two stepper motors, in which the motor control is an open-loop control. Thus, the robot’s position and orientation are computed based on the input step command for stepper motors [13]. For most differential-drive mobile drawing robots, the draw pen is installed in the middle of the wheels; therefore, this configuration is not omnidirectional in kinematics, and a sharp curve is difficult and consumes more power to draw. The motivation of this work is, thus, to explore the omnidirectional motion capability for a two-control degrees of freedom differential-drive mobile robot platform for application in fine art drawing. When the draw pen does not stall at the middle of the wheels, a differential-drive mobile robot platform may be omnidirectional and even isotropic in the Cartesian space by not considering heading control. Moreover, the mobile platform has less power consumption for a given reference following path and possibly can be used for sharp turn motions.
For the first step toward an autonomous art drawing system, the authors propose an integral system consisting of a remote main controller and a drawing mobile robot. The remote main controller can be either a personal computer (PC) or a smartphone, which automatically generates line drawing picture data from a camera in real time. The picture curves are generated in the sequence of image edge detection, searching and sorting connected paths, line simplification of image space curves, and line curve smoothing by cubic B-spline approximation. The drawing mobile robot is equipped with a pen and wireless Bluetooth connection; thus, it is able to draw pictures on a paper on-line. The robot is an accurate mobile two-wheel differential driven robot controlled by a field programmable gate array (FPGA) controller. The robot is driven by two dc servo motors. The motor control is under closed-loop position proportional-integral-derivative (PID) control. The contributions of this work are as follows:
(1)
omnidirectional motion for a differential drive mobile robot platform;
(2)
autonomous art drawing system can be built to keep both mobile robot platform and control algorithm as simple as possible; and
(3)
system integration of a mobile pen drawing platform by image edge detection, line simplification and smoothing, trajectory following control, and FPGA controller.
The rest of the paper is organized as follows: Section 2 presents an omnidirectional model of a differential-drive mobile robot. Section 3 shows trajectory tracking control methods and stability analysis. Section 4 studies trajectory planning for drawing a connected digitized curve through line simplification and line smoothing. Section 5 illustrates searching and sorting picture curves of a gray image. Section 6 provides both simulation and experimental results obtained from a test-bed mobile robot. Section 7 concludes the paper.

2. Kinematic Model of a Differential-Drive Mobile Platform

This study considers a simple mobile robot platform with two independent driving wheels and one castor free wheel. A draw pen is installed along a perpendicular line between the middle of the two wheels to depict an image picture. Let ( θ ˙ 1 , θ ˙ 2 ) be driving the wheel angular velocity, r is the radius of the driving wheel, L is half of the distance between the two wheels, and D is the perpendicular distance from the pen position to the middle of the two wheels, as shown in Figure 1. We define ( x b , y b ) as the position of the middle of the two wheels and ( x , y ) as the tip position of the pen in the world frame {W}. The origin of the robot base frame {B} is assigned to the middle of two wheels, and θ is the mobile robot yaw angle and is the orientation angle from ( x , y ) pointing to ( x b , y b ) relative to the x-axis of the world reference frame {W}, as shown in Figure 1.
Let v and ω be the instantaneous linear velocity of the origin and angular velocity of the robot base frame, respectively. The velocity kinematic equation of the mobile robot platform is represented by
[ x ˙ b y ˙ b θ ˙ ] = [ cos θ 0 sin θ 0 0 1 ] [ v ω ]
and
[ v ω ] = [ r 2 r 2 r 2 L r 2 L ] [ θ ˙ 1 θ ˙ 2 ]
Common to all types of mobile robots with two control degrees of freedom, this kinematic is not-omnidirectional. Suppose that the Cartesian position of the pen ( x , y ) is the representative point of the mobile robot platform,
[ x y ] = [ x b y b ] D [ cos θ sin θ ]
and hence,
[ x ˙ y ˙ ] = [ cos θ D sin θ sin θ D cos θ ]   [ v ω ]
The mobile robot platform kinematics without heading control is now defined by
[ x ˙ y ˙ ] = J ( θ ) [ θ ˙ 1 θ ˙ 2 ]
where the Jacobian matrix is
J ( θ ) = r 2   [ cos θ + ρ sin θ cos θ ρ sin θ sin θ ρ cos θ sin θ + ρ cos θ ]
where ratio ρ = D / L . The determinant of the Jacobian matrix, det ( J ) = ρ r 2 / 2 , is a constant. Therefore, by not locating the pen at the middle of the wheels, i.e., ρ > 0 , the Jacobian matrix is well-conditioned and the inverse Jacobian matrix is
J 1 ( θ ) = 1 r   [ cos θ + ρ 1 sin θ sin θ ρ 1 cos θ cos θ ρ 1 sin θ sin θ + ρ 1 cos θ ]
It is clear that the control degree in the yaw angle is now transformed to the control degree in the lateral linear motion. The bigger the ρ is, the larger the mobility is in the lateral motion. Without consideration of the orientation angle, the mobile robot platform becomes an omnidirectional platform in the Cartesian space. An interesting example is a circular shape robot with a pen installed at the center position.
The singular value decomposition of the Jacobian matrix J ( θ ) is
J = U Σ V T = [ u 1 u 2 ] [ σ 1 0 0 σ 2 ] [ v 1 T v 2 T ]
where
σ 1 = r 2 ,   v 1 = 1 2 [ 1 1 ] ,   u 1 = [ cos θ sin θ ]
and
σ 2 = ρ r 2 ,   v 2 = 1 2 [ 1 1 ] ,   u 2 = [ sin θ cos θ ]
The maximum and minimum singular values of the Jacobian matrix J ( θ ) are σ max = { 1 0 < ρ 1 ρ ρ > 1 and σ min = { ρ 0 < ρ 1 1 ρ > 1 , respectively; and the condition number c o n d ( J ) = σ max σ min = { ρ 1 0 < ρ 1 ρ ρ > 1 . When ρ = 1 , the condition number equals one, and the columns of the Jacobian matrix J ( θ ) are orthogonal and of equal magnitude for all robot poses. Thus, the mobile robot platform and pen system exhibit kinematic isotropy. Each wheel causes the pen’s motion to be of equal amount and orthogonal to that caused by the other wheel. In this case, it makes the best use of the degrees of freedom of the two wheels in the Cartesian motion.

3. Mobile Platform Trajectory Tracking Control Methods

3.1. Trajectory Tracking Control and Stability

As stated above, the tip position of the pen ( x ( t ) , y ( t ) ) is the representative point of the mobile robot platform, which must follow a referenced Cartesian trajectory ( x r ( t ) , y r ( t ) ) , 0 t T , in the presence of initial error. Since the Jacobian matrix J ( θ ) is well-conditioned for all poses, a simple inverse kinematics-based resolved rate plus proportional control law is applied to meet the requirement for the pen trajectory control problem.
We define e 1 ( t ) = x r ( t ) x ( t ) and e 2 ( t ) = y r ( t ) y ( t ) as the trajectory tracking errors. The control rule of resolved rate plus P control is as follows
[ θ ˙ 1 ( t ) θ ˙ 2 ( t ) ] = J 1 ( θ ^ ) [ x ˙ r ( t ) + k 1 e 1 ( t ) y ˙ r ( t ) + k 2 e 2 ( t ) ]
where θ ^ ( t ) is the estimated orientation angle θ ( t ) , and k 1 and k 2 are positive gains, k 1 , k 2 > 0 . Let θ ^ = θ + δ , and then J ( θ ) J 1 ( θ ^ ) = [ cos δ sin δ sin δ cos δ ] , and the error dynamics become a linear time-varying system as follows
[ e ˙ 1 ( t ) e ˙ 2 ( t ) ] = [ k 1 cos δ k 2 sin δ k 1 sin δ k 2 cos δ ] [ e 1 ( t ) e 2 ( t ) ] + [ 1 cos δ sin δ sin δ 1 cos δ ] [ x ˙ r ( t ) y ˙ r ( t ) ]
The stability and properties of the above closed-loop system are discussed in the following two cases.
Case 1: Global exponential stability
In the case of x ˙ r ( t ) = y ˙ r ( t ) = 0 (point-to-point motion without heading control), the closed system has a globally exponentially stable equilibrium at ( e 1 , e 2 ) = 0 . It is based on the use of the Lyapunov function V = ( e 1 2 + e 2 2 ) / 2 > 0 , ( e 1 , e 2 ) 0 , whose time derivative, V ˙ = e 1 e ˙ 1 + e 2 e ˙ 2 = cos δ   ( k 1 e 1 2 + k 2 e 2 2 ) α V , α = 2 cos δ max min { k 1 , k 2 } , provides that cos δ cos δ max > 0 and k 1 , k 2 > 0 .
Case 2: Input-to-state stability (bounded-input bounded-state stability)
Because of the bounded velocity capability of motors, the trajectory tracking velocity is limited. Assume that the derivatives of reference trajectory are limited, such that | x ˙ r ( t ) | m and | y ˙ r ( t ) | m , where m is a constant upper boundary. Lemma 4.6 of Reference [14] states that an unforced system whose trivial solution is globally exponentially stable is input-to-state stable (ISS) if submitted to a bounded input (or perturbation). Therefore, the closed system in Equation 9 is bounded-input bounded-state (BIBS) stable. Furthermore, the bounds of trajectory tracking errors are approximately | e 1 | k 1 1 δ   m and | e 2 | k 2 1 δ   m , respectively. The trajectory following errors | e 1 | and | e 2 | are directly proportional to trajectory speed m, measure error δ , and gains k 1 1 and k 2 1 .

3.2. Discrete-Time Trajectory Following Control Method

It is desirable to implement the above continuous-time trajectory control method in discrete-time form. Let T c be the trajectory control update time, and ( x r ( k ) , y r ( k ) ) is the referenced pen trajectory at discrete time k; therefore, it is likely to generate incremental motion commands Δ Ω ( k ) and Δ S ( k ) , such that
[ x b ( k ) y b ( k ) ] D   [ cos θ ( k ) sin θ ( k ) ] = [ x r ( k ) y r ( k ) ]
where
[ x b ( k ) y b ( k ) ] = [ x ( k 1 ) y ( k 1 ) ] + [ cos θ ( k 1 ) sin θ ( k 1 ) ]   ( D + Δ S ( k ) )
and
θ ( k ) = θ ( k 1 ) + Δ Ω ( k )
The above inverse kinematic equation can be rewritten as
[ cos θ ( k 1 ) sin θ ( k 1 ) ]   ( D + Δ S ( k ) ) D   [ cos ( θ ( k 1 ) + Δ Ω ( k ) ) sin ( θ ( k 1 ) + Δ Ω ( k ) ) ] = [ Δ x Δ y ]
where
[ Δ x Δ y ] = [ x r ( k ) y r ( k ) ] [ x ( k 1 ) y ( k 1 ) ]
Here, it is assumed that | Δ x | d max and | Δ y | d max , in which d max is an upper boundary on how far to move the pen in a single update time. If ( x r ( k ) , y r ( k ) ) is too distant from ( x ( k 1 ) , y ( k 1 ) ) , then it needs to move the target position in closer to the current pen location by inserting one or more intermediate points. Control terms Δ Ω ( k ) and Δ S ( k ) can be obtained as follows
Δ Ω ( k ) = sin 1 ( Δ x sin θ ( k 1 ) Δ y cos θ ( k 1 ) D )
and
Δ S ( k ) = D cos Δ Ω ( k ) D + Δ x cos θ ( k 1 ) + Δ y sin θ ( k 1 )
Motor incremental position commands are then given by
[ Δ Θ 1 ( k ) Δ Θ 2 ( k ) ] = 1 r [ Δ S ( k ) + L Δ Ω ( k ) Δ S ( k ) L Δ Ω ( k ) ]
It is also required that | Δ Θ 1 ( k ) | Δ Θ max and | Δ Θ 2 ( k ) | Δ Θ max , where Δ Θ max is the maximum incremental position command of each driving motor. Here, Δ Θ 1 ( k ) and Δ Θ 2 ( k ) are summed up and then used as absolute reference position commands of wheel motors, which are then sent to independent PID position controllers to close the dc motor servo control loops. Figure 2 shows the system block diagram of the proposed pen trajectory following control method. In this study, the trajectory control update time is T c = 20 milliseconds, and the position servo control sampling time is T s = 1.0 milliseconds.
The above trajectory control loop requires information from the mobile robot’s position and yaw angle. The computation of the mobile robot’s position and yaw angle is based on odometric prediction from motor encoders. The odometry update time is also chosen as T c = 20 milliseconds. The mobile robot’s incremental motion changes are calculated from motor encoders reading and
[ Δ s ( k ) Δ θ ( k ) ] = r   [ Δ θ 1 ( k ) + Δ θ 2 ( k ) 2 Δ θ 1 ( k ) Δ θ 2 ( k ) 2 L ]
where
[ Δ θ 1 ( k ) Δ θ 2 ( k ) ] = [ θ 1 ( k ) θ 1 ( k 1 ) θ 2 ( k ) θ 2 ( k 1 ) ]
The mobile robot base position ( x b ( k ) , y b ( k ) ) and orientation angle are updated according to
[ x b ( k ) y b ( k ) ] = [ x b ( k 1 ) y b ( k 1 ) ] + [ cos θ ( k 1 ) sin θ ( k 1 ) ]   Δ s ( k )
and
θ ( k ) = θ ( k 1 ) + Δ θ ( k )
Robot localization using the above odometry, commonly referred to as dead reckoning, is usually accurate enough in the absence of wheel slippage and backlash.

4. Line Simplification and B-Spline Smoothing

This work represents each desired picture curve by a B-spline approximation of a digitized two-dimensional image curve { x t } t = 1 N , N 2 , x t R 2 . Here, the B-spline curves of degree 1 and degree 3 are used most often. The problem statement is depicted as follows.
Given a digitized image curve of N connected pixels { x t } t = 1 N , N 2 , in order to find a two-dimensional B-spline curve of degree d,
y t = i = 1 n + d 1 N i , d ( t ) p i ,   1 t N
for (n + d − 1) control points { p i } i = 1 n + d 1 , 2 n N , it is best to approximate the sequence of input data points { ( t , x t ) } t = 1 N in a least-squares sense. The functions of N i , d ( t ) are the B-spline basis functions, which are defined recursively as:
N i , d ( t ) = t t i t i + d t i N i , d 1 ( t ) + t i + d + 1 t t i + d + 1 t i + 1 N i + 1 , d 1 ( t )
where N i , 0 ( t ) = { 1 t i t < t i + 1 0 otherwise , and 0 0 = 0 is defined.
The B-spline curve { y t } t = 1 N is then the desired pen drawing reference trajectory ( x r ( t ) , y r ( t ) ) at discrete-time t in the unit of trajectory control sampling time T c .

4.1. Line Simplification and Knot Section

The above B-spline approximation problem involves knot selection and control point selection. To simplify the solution search, knot selection and control point selection are found separately in two phases. Initially, the start and end knots are set to t 1 = 1 and t n = N . First, the line simplification technique is applied to select knots { t i } i = 1 n , 2 n N , so that 1 i < j n and 1 t i < t j N . The least-squares error method is then followed to search out new control points { p i } i = 1 n + d 1 for the purpose of line smoothing.
Line simplification is an algorithm for reducing the number of points in a curve that is approximated by a series of points within an error of epsilon. There are many line simplification algorithms—among them, the Douglas–Peucker algorithm is the most famous line simplification algorithm [15]. The starting curve is an ordered set of points or lines and the distance dimension epsilon. The algorithm recursively divides the line. It is initially given all the points between the first and last points. It automatically marks the first and last points to be kept. It then finds the point that is furthest from the line segment with the first and last points as end points; this point is obviously furthest on the curve from the approximating line segment between the end points. If the point is closer than epsilon to the line segment, then any points not currently marked to be kept can be discarded without the simplified curve being worse than epsilon. After the line simplification algorithm, the selected knots { t i } i = 1 n , 2 n N , are built from the index of line simplification points.
A linear spline approximation of the input image curve can be obtained based on the selected knots { t i } i = 1 n and control points { x t i } i = 1 n selected from those in the input dataset { x t } t = 1 N . The desired linear spline trajectory { y t } t = 1 N is then:
y t = t i + 1 t t i + 1 t i x t i + t t i t i + 1 t i x t i + 1 ,   t i t t i + 1 ,   1 i n

4.2. B-Spline Control Point Selection

This study develops the B-spline with degree d approximation of input data { x t } t = 1 N , N 2 , with distinct knots { t i } i = 1 n , 2 n N , obtained from line simplification for line smoothing. First, we define open integer knots { τ i } i = 1 n + 2 d here so that { τ i } i = 1 n + 2 d = { t 1 , , t 1 , t 2 , , t n 1 , t n , , t n } , where knots t 1 and t n repeat (d + 1) times, in order to guarantee that the start and end points of the B-spline curve are the first and last input data x 1 and x N , respectively. The B-spline curves of degree 1 and degree 3 are considered in this study.
(1) B-spline of degree 1 (d = 1)
The control points { p i } i = 1 n + d 1 are arranged here such that p 1 = x 1 and p n = x N to guarantee that the start and end points of the picture curve are unchanged, and (n − 2) control points { p i } i = 2 n 1 are left to be determined.
(2) B-spline of degree 3 (d = 3)
The control points { p i } i = 1 n + d 1 are arranged here such that p 1 = p 2 = x 1 and p n + 1 = p n + 2 = x N to guarantee zero end speeds at the start point x 1 and end point x N , and (n − 2) control points { p i } i = 3 n are left to be determined.
Control points are selected by least-squares fitting of the data with a B-spline curve:
E = 1 2 t = 1 N y t x t 2 = 1 2 t = 1 N i = 1 n + d 1 N i , d ( t ) p i x t 2
For B-spline of degree 1 (d = 1), the fitting equations are:
i = 2 n 1 N i , d ( t ) p i = b t = x t N 1 , d ( t ) x 1 N n , d ( t ) x N ,   2 t N 1
Let X = [ p 2 p 3 p n 1 ] T and B = [ b 2 b 3 b N 2 b N 1 ] T , and then we have an over-determined matrix equation:
A ( N 2 ) × ( n 2 ) X ( n 2 ) × 2 = B ( N 2 ) × 2
where A ( N 2 ) × ( n 2 ) = [ N i , d ( t ) ] , 2 t N 1 , and 2 i n 1 .
For B-spline of degree 3 (d = 3), the fitting equations are:
i = 3 n N i , d ( t ) p i = b t = x t ( N 1 , d ( t ) + N 2 , d ( t ) ) x 1 ( N n + 1 , d ( t ) + N n + 2 , d ( t ) ) x N ,   2 t N 1
Let X = [ p 3 p 4 p n ] T and B = [ b 2 b 3 b N 2 b N 1 ] T , and then we also have the same dimensions for an over-determined matrix equation:
A ( N 2 ) × ( n 2 ) X ( n 2 ) × 2 = B ( N 2 ) × 2
where A ( N 2 ) × ( n 2 ) = [ N i , d ( t ) ] , 2 t N 1 , and 3 i n .
The least-squares error solution can then be solved from the following normal equation:
S X = A T A X = A T B
or obtained from the pseudo-inverse solution:
X = ( A T A ) 1 A T B
Since the normal equation matrix S = A T A is a symmetric and banded matrix, it is, therefore, desirable to search for control points through basic row eliminations and then follow with backward substitution. Once control points { p i } i = 1 n + d 1 are found, the desired B-spline reference trajectory { y t } t = 1 N is generated through DeBoor’s B-spline recursive formulation [16].

5. Picture Curves Generation

We now describe the process from the input of the image picture to the desired picture curves’ generation. Picture curves are generated after Canny’s edge detection algorithm is performed on the input picture gray image [17]. The generation of picture draw curves involves searching and sorting picture curves in two stages. The strategy for searching out picture curves runs in three phases as stated below:
  • Phase 1: remove salt points and branch points;
  • Phase 2: search connected paths; and
  • Phase 3: search loop paths.
The picture point decision is based on the local information of its adjacent pixels in a 3-by-3 window, [ P 8 P 1 P 5 P 4 pixel P 2 P 7 P 3 P 6 ] , defined here. Let the terms 4-connect and 8-connect of a pixel point be the numbers of its 4-connected pixel equal to 1 and its 8-connected pixel equal to 1, respectively.
In phase 1, salt point and branch point are classified as below:
  • salt point: 8-connect = 0; and
  • branch point: 4-connect > 2.
In phase 2, start point, mid-point, and end point of a connected path are classified as below:
  • start point: 4-connect = 1 or (4-connect = 0 and 8-connect = 1);
  • mid-point: in the order of (P1 = 1) or (P2 = 1) or (P3 = 1) or (P4 = 1) or (P5 =1) or (P6 = 1) or (P7 = 1) or (P8 = 1);
  • end point: 8-connect = 0.
In phase 3, salt point and point in a loop path are classified as below:
  • salt point: 8-connect = 0;
  • point in a loop path: 8-connect ≥ 2.
For the sorting of final picture curves, a simple greedy method of the nearest neighbor strategy is applied to sort picture curves in order to send out to the robot drawer. The next curve to be drawn is the one where one of its end points is closest to the end position of the drawing curve among the rest of the curves. Figure 3 shows picture curve search results; the input gray image has a size of 213 × 315 bytes. There are 5878 edge pixels after edge detection, and there are 136 connected curves in curve sorting. After line simplification, there are 2702 control points left.

6. Simulation and Experimental Results

The experimental autonomous robot image figure drawing system consists of a PC or a smartphone as a main controller and a differential-drive mobile robot platform as shown in Figure 4. The radius of the driving wheel is r = 56.25 mm, and the distance of two driving wheels is 2 L, where L = 12.25 mm. The wheel is actuated by a dc motor (motor maximum no-load speed 4290 rpm) with a 15:1 gear reducer, and the motor encoder has a resolution of 30,000 ppc. The proposed pen trajectory following control system is built on an Altera DE0-nano FPGA development board running at a system clock rate of 50 MHz. All control and series communication modules are implemented using Verilog hardware description language (HDL) and synthesized by an Altera Quartus II EDA tool. The image processing and connected curve generation program are programmed in Visual C++ for PC and in JAVA for smartphone. The mobile robot receives real-time picture curves data, which are generated from a PC or a smartphone through Bluetooth rs232 at a Baud-rate of 115,200 Hz.
The first example considers a circular path to verify the effect of ρ = D / L . The desired reference path trajectory is represented by x r ( t ) = R cos ( ω t ) and y r ( t ) = R cos ( ω t ) , 0 t t f = 2 π / ω , where R = 50 mm, and the total circular length is S = 0 t f x ˙ r 2 + y ˙ r 2   d t = 100p mm. The control law in Equation (8) with proportional gains k 1 = k 2 = 20 is used. Figure 5 shows the total displacement Θ = 0 t f θ ˙ 1 2 + θ ˙ 2 2   d t in the joint space with respect to arbitrary initial yaw angle θ 0 for several different pen location distances D to follow the desired circular path trajectory.
The second example considers a square path of side length 100 mm, and the total length is S = 0 t f x ˙ r 2 + y ˙ r 2   d t = 400 mm. Figure 6 shows the total displacement Θ = 0 t f θ ˙ 1 2 + θ ˙ 2 2   d t in the joint space with respect to initial angle yaw θ 0 for several different pen location distances D to follow the desired square path trajectory. As expected, the joint space displacement Θ decreases as the distance D increases. When ρ = 1 (i.e., D = L), the Jacobian matrix J is isotropic for all mobile robot poses; and hence, Θ is independent on the mobile robot initial yaw angle θ 0 and Θ = 2 S / r .
In the following trajectory control experiments, a drawing pen is located at a distance of D = 50 mm. The discrete-time trajectory following control law in Equations (11) and (12) is applied with trajectory and feedback update time T s = 0.01 s. Figure 7 and Figure 8 show the experimental mobile robot’s drawn results of a circular path (radius 50 mm) and a square path (side length 100 mm), respectively. For both curves, the trajectory following error is within 3.0 mm without initial position error. It is shown that the pen tip trajectory has small trajectory tracking errors in sharp turn corners in Figure 8.
Figure 9 shows the experimental drawn results of Taiwan maps. The origin data has 1105 discrete data points, and there are 42 control points in its line simplification curve, and 44 control points in the cubic B-spline smoothing curve. Figure 10 shows tracking errors of drawn Taiwan maps in Figure 9. The drawing size is 160 × 80 mm2, tracking errors are within 1.0 mm, and drawing time is 10 s. Since the step size is small, there are few differences in Figure 10.
Figure 11 shows the drawn results of a building image in Figure 3, in which there are 136 connected curves with 2702 control points in total after procedures of edge detection and line simplification. The drawing size is 150 × 120 mm2 and drawing time is about 90 s.
Figure 12 shows the image drawn by the experimental mobile robot of a human portrait. The original image is 280 × 210 pixels and has 3951 pixels after edge detection, and it leaves 100 connected curves with 2267 control points after line simplification. The drawn picture size is 8.0 × 5.0 cm2 and is done in about 60 s.

7. Conclusions

What is new in this present research is that by removing the control degree in yaw angle to a linear lateral motion of a differential-drive mobile robot, an omnidirectional platform can be built. Thus, we can design an autonomous art drawing platform in a closed-loop fashion through an inverse kinematics plus proportional control approach. Both simulation and experimental results show that the experimental system works in practice as well as in theory. The limitations of the current system are a lack of heading control in trajectory tracking control and slower motion of the mobile system. Further works can include integrating the vision system in the FPGA, refining the mobile robot odometry for longer traveling distance, and developing fast speed motion controller.

Acknowledgments

This work is supported by grants from Taiwan’s Ministry of Science and Technology, MOST 105-2221-E-011-047 and 106-2221-E-011-151.

Author Contributions

C.-L. Shih and L.-C. Lin conceived and designed the experiments; L.-C. Lin performed the experiments; C.-L. Shih and L.-C. Lin analyzed the data; C.-L. Shih wrote the paper.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Kotani, S.; Yasutomi, S.; Kin, X.; Mori, H.; Shigihara, S.; Matsumuro, Y. Image processing and motion control of a lane mark drawing robot. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Yokohama, Japan, 26–30 July 1993; pp. 1035–1041. [Google Scholar]
  2. Srikaew, A.; Cambron, M.; Northrup, S.; Peters, R.A., II; Wilkes, M.; Kawamura, K. Humanoid drawing robot. In Proceedings of the IASTED International Conference on Robotics and Manufacturing, Banff, AB, Canada, 26–29 July 1998. [Google Scholar]
  3. Lau, M.C.; Baltes, J.; Anderson, J.; Durocher, S. A portrait drawing robot using a geometric graph approach: Furthest Neighbour Theta-graphs. In Proceedings of the IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM), Kachsiung, Taiwan, 11–14 July 2012; pp. 75–79. [Google Scholar]
  4. Tresset, P.; Leymarie, F.F. Portrait drawing by Paul the robot. Comput. Gr. 2013, 37, 348–363. [Google Scholar] [CrossRef]
  5. Jain, S.; Gupta, P.; Kumar, V.; Sharma, K. A force-controlled portrait drawing robot. In Proceedings of the IEEE International Conference on Industrial Technology (ICIT), Seville, Spain, 17–19 March 2015; pp. 3160–3165. [Google Scholar]
  6. Kanayama, Y.; Kimura, Y.; Miyazaki, F.; Noguchi, T. A stable tracking control method for an autonomous mobile robot. In Proceedings of the IEEE International Conference on Robotics and Automation, Cincinnati, OH, USA, 13–18 May 1990; pp. 384–389. [Google Scholar]
  7. Samson, C. Control of chained systems application to path following and time-varying point-stabilization of mobile robots. IEEE Trans. Autom. Control 1995, 40, 64–77. [Google Scholar] [CrossRef]
  8. Egerstedt, M.; Hu, X.; Stotsky, A. Control of mobile platforms using a virtual vehicle approach. IEEE Trans. Autom. Control 2001, 46, 1777–1782. [Google Scholar] [CrossRef]
  9. Saha, S.K.; Angeles, J.; Darcovich, J. The kinematic design of a 3-DOF isotropic mobile robot. In Proceedings of the IEEE International Conference on Robotics and Automation, Atlanta, GA, USA, 2–6 May 1993; pp. 283–288. [Google Scholar]
  10. Togai, M. An application of singular value decomposition to manipulability and sensitivity of industrial robots. SIAM J. Algebraic Discret. Methods 1986, 7, 315–320. [Google Scholar] [CrossRef]
  11. Merlet, J.-P. Jacobian, manipulability, condition number and accuracy of parallel robots. ASME J. Mech. Des. 2006, 128, 199–206. [Google Scholar] [CrossRef]
  12. Durina, D.; Petrovic, P.; Balogh, R. Robotnacka—The drawing robot. Acta Mech. Slov. 2006, 10, 113–118. [Google Scholar]
  13. Balogh, R. Practical kinematics of the differential driven mobile robot. Acta Mech. Slov. 2007, 11, 11–16. [Google Scholar]
  14. Khalil, H.K. Nonlinear Systems, 3rd ed.; Prentice-Hall: Upper Saddle River, NJ, USA, 2002. [Google Scholar]
  15. Douglas, D.H.; Thomas, K.; Peucker, T.K. Algorithms for the reduction of the number of points required to represent a digitized line or its caricature. Can. Cartogr. 1973, 10, 112–122. [Google Scholar] [CrossRef]
  16. De Boor, C. A Practical Guide to Splines, revised version; Springer: New York, NY, USA, 2001. [Google Scholar]
  17. Canny, J. A Computational Approach to Edge Detection. IEEE Trans. Pattern Anal. Mach. Intell. 1986, 8, 679–698. [Google Scholar] [CrossRef] [PubMed]
Figure 1. Coordinate frames of the mobile robot platform and pen system: the world frame {W} and robot base frame {B} with origin at the middle of two wheels. A draw pen is installed along a perpendicular line between the middle of the two wheels.
Figure 1. Coordinate frames of the mobile robot platform and pen system: the world frame {W} and robot base frame {B} with origin at the middle of two wheels. A draw pen is installed along a perpendicular line between the middle of the two wheels.
Robotics 06 00017 g001
Figure 2. The system block diagram of the pen trajectory following control.
Figure 2. The system block diagram of the pen trajectory following control.
Robotics 06 00017 g002
Figure 3. Image picture curves search results: (a) original image; (b) edge detection results; and (c) searched picture curves.
Figure 3. Image picture curves search results: (a) original image; (b) edge detection results; and (c) searched picture curves.
Robotics 06 00017 g003
Figure 4. A differential-drive mobile robot platform with a draw pen to generate a picture from an image.
Figure 4. A differential-drive mobile robot platform with a draw pen to generate a picture from an image.
Robotics 06 00017 g004
Figure 5. Simulation results of the effect of ρ for a differential-drive mobile robot to follow in a circular path.
Figure 5. Simulation results of the effect of ρ for a differential-drive mobile robot to follow in a circular path.
Robotics 06 00017 g005
Figure 6. Simulation results of the effect of ρ for a differential-drive mobile robot to follow in a square path.
Figure 6. Simulation results of the effect of ρ for a differential-drive mobile robot to follow in a square path.
Robotics 06 00017 g006
Figure 7. Experimental drawn results of the pen tip trajectory following control of a circular path with a radius of 50 mm. (a) desired and drawn circular paths; (b) tracking error and orientation angle.
Figure 7. Experimental drawn results of the pen tip trajectory following control of a circular path with a radius of 50 mm. (a) desired and drawn circular paths; (b) tracking error and orientation angle.
Robotics 06 00017 g007
Figure 8. Experimental drawn results of the pen tip trajectory following control of a square curve path with side lengths of 100 mm. (a) desired and drawn square paths; (b) tracking error and orientation angle.
Figure 8. Experimental drawn results of the pen tip trajectory following control of a square curve path with side lengths of 100 mm. (a) desired and drawn square paths; (b) tracking error and orientation angle.
Robotics 06 00017 g008
Figure 9. Experimental drawn results of Taiwan maps: (a) original map; (b) desired line simplification curve; (c) desired cubic B-spline curve; (d) drawn Taiwan map (from line simplification) and (e) drawn Taiwan map (from line smoothing).
Figure 9. Experimental drawn results of Taiwan maps: (a) original map; (b) desired line simplification curve; (c) desired cubic B-spline curve; (d) drawn Taiwan map (from line simplification) and (e) drawn Taiwan map (from line smoothing).
Robotics 06 00017 g009
Figure 10. Tracking errors of drawn Taiwan maps in Figure 9d,e.
Figure 10. Tracking errors of drawn Taiwan maps in Figure 9d,e.
Robotics 06 00017 g010
Figure 11. Drawn result of a building image compared to (a) the original image; (b) searched picture curves; and (c) drawn picture.
Figure 11. Drawn result of a building image compared to (a) the original image; (b) searched picture curves; and (c) drawn picture.
Robotics 06 00017 g011
Figure 12. Image drawn by the mobile robot is compared to (a) the original image; (b) searched picture curves; and (c) drawn picture.
Figure 12. Image drawn by the mobile robot is compared to (a) the original image; (b) searched picture curves; and (c) drawn picture.
Robotics 06 00017 g012

Share and Cite

MDPI and ACS Style

Shih, C.-L.; Lin, L.-C. Trajectory Planning and Tracking Control of a Differential-Drive Mobile Robot in a Picture Drawing Application. Robotics 2017, 6, 17. https://doi.org/10.3390/robotics6030017

AMA Style

Shih C-L, Lin L-C. Trajectory Planning and Tracking Control of a Differential-Drive Mobile Robot in a Picture Drawing Application. Robotics. 2017; 6(3):17. https://doi.org/10.3390/robotics6030017

Chicago/Turabian Style

Shih, Ching-Long, and Li-Chen Lin. 2017. "Trajectory Planning and Tracking Control of a Differential-Drive Mobile Robot in a Picture Drawing Application" Robotics 6, no. 3: 17. https://doi.org/10.3390/robotics6030017

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