A Probability-Based Path Planning Method Using Fuzzy...

7
A Probability-based Path Planning Method Using Fuzzy Logic Jaeyeon Lee and Wooram Park Abstract—In this paper, we improve the path-of-probability (POP) algorithm to generate better and smoother paths for robotic systems. The POP algorithm generates a full path with the maximum probability to reach a target. Although the POP algorithm has been successfully applied to path generation of robotic systems, it has the limit that the intermediate paths are generated using a finite and small number of candidate paths. This results in non-smooth (or zigzag pattern) paths which are not desirable for practical use. In addition, this approach sometimes fails to generate a path that reaches a target. This can be overcome by increasing the number of candidate paths, but it increases the computation time too. To improve the POP method, we use a fuzzy logic. The fuzzy logic enables us to obtain a continuous set for the intermediate paths from the discrete candidate paths. By applying it, smoother paths from the starting point to the target can be obtained directly without any additional path smoothing because the intermediate paths are chosen from a continuous set. Fundamentally, the fuzzy logic makes a mapping from a finite and discrete set of candidate paths to a continuous set of paths. We apply the proposed method to path planning for a two wheeled robot and a flexible needle. The simulation results confirm the performance of the proposed approach. I. INTRODUCTION Most technologies in robotic research use theoretical mod- els for analysis and simulation. However, the models cannot be accurate enough to express the natural phenomenon because simplification is inevitable in modeling due to the system complexity. Therefore, stochasticity of systems is ignored in many cases by employing deterministic models. Usually, there exist uncertainties such as model errors and disturbances in actual systems. Along this line, many studies have been done on stochasticity and it was included in the theoretical model for the purpose of better analysis [1], [2] and control [3]. Based on a stochastic model, which is usually implemented as a stochastic differential equation, a path planning method called path-of-probability (POP) method was developed and applied to engineering problems and medical application. The POP algorithm generates a full path by obtaining and stitching multiple intermediate paths which maximize the probability to reach a target. This method was firstly introduced in [4] to solve inverse kinematics problems and then applied widely [5], [6], [7], [8]. Even though the POP algorithm has been successfully used for path and motion planning for robot systems, the POP algorithm implemented in the previous works still needs to be improved in several aspects. Above all, the intermediate Jaeyeon Lee is with the Department of Electrical Engineering, University of Texas at Dallas, 800 W. Campbell Rd., Richardson, TX, USA. W. Park is with the Department of Mechanical Engineering, Uni- versity of Texas at Dallas, 800 W. Campbell Rd., Richardson, TX, USA.{jaeyeon.lee, wooram.park}@utdallas.edu paths can only be selected from a finite and discrete set of candidates which are pre-defined. Due to this limitation, the full paths may be non-smooth and contain sharp edges without additional path smoothing process. In worse cases, the path obtained by the current POP method may fail to reach a target close enough. As one effective method to deal with this drawback, we introduce an idea of the fuzzy logic system. For the recent decades, the fuzzy logic has drawn consid- erable attention because of its ability to deal with numerical and linguistic data knowledge simultaneously since firstly introduced by Zadeh [9] in 1965. According to Zadeh in [10], the fuzzy logic is a precise logic of imprecision and approximate reasoning. The fuzzy logic can perform a wide variety of physical and mental tasks without any measure- ments and computations [11], [12]. Most physical systems in real world are highly nonlinear, do not allow linearization and are quite difficult to mathematically model. The fuzzy logic can suggests an alternative approach to overcome these difficulties based on the knowledge and experiences of a system designer unlike classical approaches that require deep quantitative understanding for a system. A principal benefit of the fuzzy logic is that any nonlinear function can be approximated through a universal approximator [13]. A number of related approaches adopting this capability were developed in [14], [15], [16], [17]. In this paper, we are motivated by the capability of the fuzzy logic that it can map a discrete set to a continuous one. The combined technique of the POP and the fuzzy logic will generate smoother paths directly, and will increase the success rate to reach targets. This paper is organized as fol- lows. In Section II, related works for the POP method, path smoothing and the fuzzy logic are reviewed. In Section III, the details of the proposed method which is the POP method combined with the fuzzy logic are presented. In Section IV, the proposed technique is applied to a two wheeled robot and a flexible medical needle, and the simulation results are presented. Finally, the conclusion is given in Section V. II. RELATED WORKS In this section, we present a summary for the stochastic differential equation which express the behavior and property of a system with the stochasticity. The path-of-probability (POP) algorithm for path planning is introduced and then path smoothing will be briefly discussed. Finally, general knowledge of the fuzzy logic system (FLS) will be followed. 2014 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2014) September 14-18, 2014, Chicago, IL, USA 978-1-4799-6934-0/14/$31.00 ©2014 IEEE 2978

Transcript of A Probability-Based Path Planning Method Using Fuzzy...

A Probability-based Path Planning Method Using Fuzzy Logic

Jaeyeon Lee and Wooram Park

Abstract— In this paper, we improve the path-of-probability(POP) algorithm to generate better and smoother paths forrobotic systems. The POP algorithm generates a full path withthe maximum probability to reach a target. Although the POPalgorithm has been successfully applied to path generation ofrobotic systems, it has the limit that the intermediate paths aregenerated using a finite and small number of candidate paths.This results in non-smooth (or zigzag pattern) paths whichare not desirable for practical use. In addition, this approachsometimes fails to generate a path that reaches a target. Thiscan be overcome by increasing the number of candidate paths,but it increases the computation time too. To improve thePOP method, we use a fuzzy logic. The fuzzy logic enablesus to obtain a continuous set for the intermediate paths fromthe discrete candidate paths. By applying it, smoother pathsfrom the starting point to the target can be obtained directlywithout any additional path smoothing because the intermediatepaths are chosen from a continuous set. Fundamentally, thefuzzy logic makes a mapping from a finite and discrete setof candidate paths to a continuous set of paths. We applythe proposed method to path planning for a two wheeledrobot and a flexible needle. The simulation results confirm theperformance of the proposed approach.

I. INTRODUCTION

Most technologies in robotic research use theoretical mod-els for analysis and simulation. However, the models cannotbe accurate enough to express the natural phenomenonbecause simplification is inevitable in modeling due to thesystem complexity. Therefore, stochasticity of systems isignored in many cases by employing deterministic models.Usually, there exist uncertainties such as model errors anddisturbances in actual systems. Along this line, many studieshave been done on stochasticity and it was included in thetheoretical model for the purpose of better analysis [1],[2] and control [3]. Based on a stochastic model, whichis usually implemented as a stochastic differential equation,a path planning method called path-of-probability (POP)method was developed and applied to engineering problemsand medical application. The POP algorithm generates afull path by obtaining and stitching multiple intermediatepaths which maximize the probability to reach a target.This method was firstly introduced in [4] to solve inversekinematics problems and then applied widely [5], [6], [7],[8]. Even though the POP algorithm has been successfullyused for path and motion planning for robot systems, the POPalgorithm implemented in the previous works still needs tobe improved in several aspects. Above all, the intermediate

Jaeyeon Lee is with the Department of Electrical Engineering, Universityof Texas at Dallas, 800 W. Campbell Rd., Richardson, TX, USA.

W. Park is with the Department of Mechanical Engineering, Uni-versity of Texas at Dallas, 800 W. Campbell Rd., Richardson, TX,USA.{jaeyeon.lee, wooram.park}@utdallas.edu

paths can only be selected from a finite and discrete setof candidates which are pre-defined. Due to this limitation,the full paths may be non-smooth and contain sharp edgeswithout additional path smoothing process. In worse cases,the path obtained by the current POP method may fail toreach a target close enough. As one effective method to dealwith this drawback, we introduce an idea of the fuzzy logicsystem.

For the recent decades, the fuzzy logic has drawn consid-erable attention because of its ability to deal with numericaland linguistic data knowledge simultaneously since firstlyintroduced by Zadeh [9] in 1965. According to Zadeh in[10], the fuzzy logic is a precise logic of imprecision andapproximate reasoning. The fuzzy logic can perform a widevariety of physical and mental tasks without any measure-ments and computations [11], [12]. Most physical systemsin real world are highly nonlinear, do not allow linearizationand are quite difficult to mathematically model. The fuzzylogic can suggests an alternative approach to overcomethese difficulties based on the knowledge and experiencesof a system designer unlike classical approaches that requiredeep quantitative understanding for a system. A principalbenefit of the fuzzy logic is that any nonlinear function canbe approximated through a universal approximator [13]. Anumber of related approaches adopting this capability weredeveloped in [14], [15], [16], [17].

In this paper, we are motivated by the capability of thefuzzy logic that it can map a discrete set to a continuousone. The combined technique of the POP and the fuzzy logicwill generate smoother paths directly, and will increase thesuccess rate to reach targets. This paper is organized as fol-lows. In Section II, related works for the POP method, pathsmoothing and the fuzzy logic are reviewed. In Section III,the details of the proposed method which is the POP methodcombined with the fuzzy logic are presented. In Section IV,the proposed technique is applied to a two wheeled robotand a flexible medical needle, and the simulation results arepresented. Finally, the conclusion is given in Section V.

II. RELATED WORKS

In this section, we present a summary for the stochasticdifferential equation which express the behavior and propertyof a system with the stochasticity. The path-of-probability(POP) algorithm for path planning is introduced and thenpath smoothing will be briefly discussed. Finally, generalknowledge of the fuzzy logic system (FLS) will be followed.

2014 IEEE/RSJ International Conference onIntelligent Robots and Systems (IROS 2014)September 14-18, 2014, Chicago, IL, USA

978-1-4799-6934-0/14/$31.00 ©2014 IEEE 2978

(a) (b)

Fig. 1. Schematic presentation of the POP algorithm. The points g0 andggoal denote the starting point and the destination, respectively. The twocandidate paths (gi) from the same current location (gi−1) are comparedin terms of probability of reaching the goal.

A. Stochastic differential equation

In real world, all systems contain certain amount of modeluncertainty and disturbance. Therefore, a better model todescribe the system’s behavior should include the stochasticeffects. A stochastic differential equation (SDE) can repre-sent a kinematic or dynamic motion of a system with thestochastic effects. The SDE can be written in Rn as

dx(t) = h(x(t), t)dt+H(x(t), t)dW(t) (1)

where x ∈ Rn is a state variable and H ∈ Rn×m is a matrixthat scales and couples the noise W ∈ Rm. This SDE canbe obtained by perturbing the deterministic model dx/dt =h(x, t) by noise or random force presented by a vector ofuncorrelated unit strength Wiener process W(t). Eventually,we need to find a time-dependent probability density functionρ(x, t) of x(t) from the SDE because every system variablex(t) obtained by integrating the SDE (1) is different for everytime due to the stochasticity. One simple way to obtain theprobability density function ρ(x, t) from the SDE (1) is touse Euler-Maruyama method [18] to numerically integratethe SDE (1) a number of times and build the histogram.An example of the numerical integration using the Euler-Maruyama method appeared in [5].

B. Path-of-probability (POP) Algorithm

The POP algorithm effectively generates the optimal pathfrom a starting point to a target using the probability densityfunction of the stochastic system. A whole path is obtainedby stitching multiple intermediate paths. Each intermediatepath is determined such that the probability that the futurepath may reach the target is maximized. Figure 1 represents aschematic presentation of the POP algorithm. The points g0,gi and ggoal denote a starting point, an intermediate pointand the goal position, respectively. The ellipses representsthe probability density function of the position of the futurepath. For each step, we evaluate which intermediate pointshould be selected using the probability. In Figure 1, weassume that the paths in the two cases are the same from g0to gi−1. Then, we compare the two different candidates for

Fig. 2. Block diagram of Fuzzy logic system

gi using the probability. Figure 1(b) shows the better choiceof gi than Figure 1(a) because it gives the higher probabilitythat the future path will hit the goal. However the currentPOP algorithm has limitations. Because every intermediatepath in this method is selected from a pre-defined discreteset, it results in non-smooth paths and sometimes fails toreach a target close. At this point, we need an idea for pathsmoothing.

C. Path smoothing

The paths obtained from path planning may have sharpedges which may not be suitable for practical use becausethe path requires the system to make sharp turns and thusthe extremely high control input may be required. The pathsmoothing has been an interesting topic in the path planningcommunity. Since the excellent work by Dubins [19], manypath smoothing methods have been developed based onDubins curves [20], [21] in which the shortest path canbe obtained by the combination of straight line segmentsand arcs of circles. In [22], [23], the authors used thespline for smoothing the path. Other researchers discusseda method to generate the trajectory that satisfies the pathconstraints with Bezier curves in [24]. The authors in [25]smoothed off the sharp edges of the path based on parametriccubic Bezier curves. However, all these works employ twoseparated routines (path planning and path smoothing) for thewhole path planning. Recently, there are also path planningtechniques that generate smooth path in [26], [27], [28], [29],[30]. However, these methods are internally based on the twoseparated steps and their paths are not generated based on theprobability to target the goal but the path length. Thereforethey are not suitable for the stochastic system. Note thatthe major purpose of this paper is to advance the classicPOP method by continuously searching intermediate pathcandidates using the fuzzy logic system.

D. Fuzzy logic system (FLS)

Since Zadeh [9] invented the concept of fuzzy logic in1965, it has been widely applied. A fuzzy system generallyconsists of four components such as Fuzzifier, Rule-Base,Inference Engine, and Defuzzifier as shown in Figure 2. Anonlinear mapping between input and output is achieved bya procedure below. The crisp input is interpreted in Fuzzifierand then is applied to fuzzy rules. The Rule-base has a setof IF-THEN rules which connect the crisp input to the crispoutput. In the Inference Engine, the relevance of each rule

2979

is evaluated to generate the output. The Defuzzifier convertsthe linguistic output from the Inference Engine into a crispoutput. Because the fuzzy logic system is a knowledge-based system, the user does not have to develop a complexmathematical model. This capability enables the fuzzy logicsystem to be used in many areas such as prediction, systemidentification, and control.

III. PATH PLANNING

The path planning based on probability can be effectivelyachieved for a stochastic system using the POP algorithm.In this section, we apply the probability-based path planningstrategy to a two wheeled mobile robot moving on the 2Dspace and a flexible needle steered in the 3D space. Thefuzzy logic system is combined with the POP method toobtain improved results.

A. Two wheeled robot

According to the work in [6], the kinematic model of thetwo wheeled robot shown in Figure 3 for the infinitesimalmotions governed by no-lateral-slip conditions is written as dx

dydθ

=

rωCθrωSθγ

dt+ σ

r2Cθ r

2Cθr2Sθ

r2Sθ

rL − r

L

[dW1

dW2

](2)

where Cθ = cos θ, Sθ = sin θ and dW is the incrementof unit-strength Wiener process, and σ denotes the strengthof the Wiener process. γ is 2rδ/L and δ is a difference ofangular velocity between two wheels such that ω1 = ω + δand ω2 = ω − δ. This equation expresses the motion of thetwo wheeled robot with stochastic effects which are appliedon the angular velocity of two wheels. The POP algorithmin [4], [5], [7], [31], [32] can be used to generate paths forthe two wheeled robot as follows. We assume a simple inputangular velocity ω = 0.1 with δ = 0 for the two wheeledrobot model. After the robot moves with the angular velocityω and δ in a deterministic way during a small time period ∆t,the robot will arrive at the next intermediate position whichis a deterministic position. This small path is a simple +xdirection of motion. To evaluate if this is the best positionof the intermediate point in terms of the probability, weshould compare probabilities using other candidate positions.A candidate position with which the future path has thehighest probability of reaching the goal is selected. For oursimulation test, we suggest the following options for eachstep as the candidates.

δ = −α or 0 or α. (3)

where α is a positive value for difference between twowheels’ angular velocities. We compute the probability thatthe final path can reach the goal for each option value δ.

To get the probability density function, we follow severalsteps. Multiple random paths are obtained using Euler-Maruyama method [18] that is a numerical integrationmethod for stochastic differential equations. Then, a his-togram is calculated and a probability density function can beestimated by smoothing the histogram using small Gaussian

Fig. 3. The kinematic model of the two wheeled robot [6]

−0.08 −0.06 −0.04 −0.02 0 0.02 0.04 0.06 0.080

0.5

1

1.5

Difference between two wheels (δ)

TR TL

Fig. 4. Output membership function of the two wheeled robot

kernels. This smoothing method for the histogram has beenused in [8]. The probability density function can be writtenas

p(x, y) =1

n

n∑k=1

gk(x, y) (4)

where gk(x, y) is the Gaussian distribution function whosemean and variance are (xk, yk) and s2, respectively. (xk, yk)is the final position of the kth path from the numerical inte-gration of the SDE. Using s we can control the smoothnessof the histogram.

The POP algorithm selects the optimal choice for δ from(−α, 0, α) using the probability density function. However,this approach has a drawback that the chosen parameter δshould be one of the three discrete and pre-defined values,which means the algorithm does not allow a selection forδ in continuous range. Therefore, the whole path may notbe sufficiently smooth and sometimes fails to reach the goal.More candidate values can be used to generate smooth paths,but it increases the computational time also. To overcomethis, we incorporate the POP method with the fuzzy logicsystem.Using IF-THEN form’s rule, we can infer the opti-mal parameter among the candidates. In other words, thisnew approach enables the continuous search using discretesamples. To show the significant benefit of the fuzzy logicfor the POP method, we prepare only two candidates as

δ = −α or α. (5)

The output membership function for the fuzzy logic systemto generate a final smooth path is simply designed with Rand L function as shown in Figure 4. [TL] and [TR] denoteoutput fuzzy sets [Turn Left] and [Turn Right], respectively.The probability density function in the POP algorithm canbe used as an input membership function. It makes sensebecause we only evaluate a weight of the probability densityfunction that the target point is hit from each candidate value.

2980

For the inference, the IF-THEN rules are suggested as{IF ρ(α) > ρ(−α), THEN ωz = Turn Left (TL),IF ρ(−α) > ρ(α), THEN ωz = Turn Right (TR).

(6)where ρ(α) is the probability that the future path may reacha target when we chose δ = α for the intermediate path. Inthe defuzzification step, the crisp output is obtained using thecentroid (center of gravity) technique which can be expressedas

C =

∫µi(x)xdx∫µi(x) dx

(7)

where C is the defuzzified output, µi(x) is the aggregatedmembership function and x is the output variable. Thedefuzzified crisp output is used as the optimal differencebetween two wheels’ angular velocities for each intermediatepath that the two wheeled robot should follow to reach thedesired goal position.

B. Flexible needle

A flexible needle with a bevel tip was introduced in [33]and it drew attention due to its potential that it can follow a3D smooth curve when inserted for medical purposes. Thenonholonomic kinematic model for the flexible needle isgiven as [33]

ξ = (g−1g)∨ = [κv(t) 0 ω(t) 0 0 v(t)]T , (8)

where κ is the needle curvature generated by the bevel tip, gis the homogeneous transformation matrix representing thepose of the body frame attached to the needle tip, and ξis the body velocity of the frame. As shown in Figure 5,two inputs, v(t) and ω(t) are used to control the flexibleneedle. As a starting point, we first apply the unit insertionspeed v(t) = 1. In the nature, some amount of errors mightbe added into the deterministic model described in (8). Onesimple way to capture the stochastic effect is to introduce anoise term into the rotational input as [7]

ω(t) = ω0(t) + λw(t), (9)

where ω0(t) is the nominal angular velocity for needlerotation, λ is the noise parameter and w(t) is the Gaussianwhite noise. Therefore, the new needle model with thestochastic effect of (9) can be written as

(g−1g)∨dt = [k 0 ω0 0 0 1]T dt+ [0 0 λ 0 0 0]T dW,(10)

where dW = W (t + dt) − W (t) = w(t)dt is the non-differentiable increment of a Wiener process W (t). Thismodel can be expressed with a stochastic differential equa-tion (SDE) on SE(3) as

(g−1g)∨dt = hdt+HdW(t). (11)

The numerical integration of SE(3) for this model can bewritten as

gi+1 = gi exp (ξ), (12)

where gi = g(ti), ξ = h∆ti + H∆Wi and exp(·) is thematrix exponential. The numerical integration (12) gives

Fig. 5. Parameters and frames of the nonholonomic needle model

Fig. 6. Output membership function for the flexible needle

multiple needle positions, and a histogram can be obtainedusing them. Then the probability density function can beestimated by smoothing the histogram using the 3D Gaussiankernel. The probability density function can be defined byextending (4) to the three dimensional domain.

In order to apply the POP method, we suggest the follow-ing three candidate angular velocities as

ω0 = −β or 0 or β. (13)

At every intermediate step, the rotation angular velocityaround z-axis is determined such that the probability ismaximized. Since the rotation of the needle around theneedle axis is not bounded, the rotation angle should cover 0to 2π radian. Therefore, we choose β = 2π/3 and the timestep between intermediate paths is set to be 1 sec.

We also apply the fuzzy method to this needle problem.The output membership function is designed in 3D spaceas shown in Figure 6 because a range of the needle rotation

0.20.4

0.60.8

30

210

60

240

90

270

120

300

150

330

180 0 (θ)

(r)

Fig. 7. Center of mass in the polar coordinates

2981

0 50 100−50

0

50

X

Y

(a)

0 50 100−50

0

50

X

Y

(b)

Fig. 8. Path by POP and POP with fuzzy logic for the two wheeled robot

should cover 0 to 2π. The estimated probability density func-tion can be directly used as an input membership function.In the inference step, we use IF-THEN rules as IF ρ(β) > max{ρ(0), ρ(−β)}, THEN ω0 = β (TP ),

IF ρ(0) > max{ρ(β), ρ(−β)}, THEN ω0 = 0 (SZ),IF ρ(−β) > max{ρ(0), ρ(β)}, THEN ω0 = −β (TN)

(14)where ρ(β) is the probability that the future path may reach atarget when we chose ω0 = β for the intermediate path. Forthe defuzzification step, we introduce the polar coordinates inorder to evaluate a relevance point among three output fuzzysets (TN, SZ, and TP). Each output fuzzy set is multipliedby the weight obtained from the input membership function.After the output membership function defined as shown inFigure 6 is multiplied by the weight, we map the membershipfunction to the polar coordinates as shown in Figure 7. Thecrisp output can be obtained by computing the center of massfor the uniform area in the polar coordinates. The center ofmass is shown as a star mark in Figure 7. The defuzzifiedcrisp output is used as the optimal value for the angularvelocity ω0.

IV. NUMERICAL EXAMPLES

In this section, we verify the performance of the proposedmethod using simulation. We generate the paths for the twowheeled robot and the flexible needle in the environmentwith and without an obstacle. The simulation parameters areshown in Table I.

Two wheeled robot Flexible needle# of random paths 500 500# of path segments 10 10Total simulation time (sec) 100 10Bin size 1 × 1 0.1 × 0.1

TABLE ISIMULATION PARAMETERS

A. Two wheeled robot

The paths of the two wheeled robot without an obstacleare shown in Figure 8. While a path by the POP is lesssmooth and does not reach the target accurately as shownin Figure 8(a), the POP with the fuzzy logic generates a

Fig. 9. Defuzzification for each intermediate step of the two wheeled robot

0 50 100−50

0

50

X

Y(a)

0 50 100−50

0

50

X

Y

(b)

Fig. 10. Path generation with an obstacle by POP and POP with fuzzylogic for the two wheeled robot

smoother path that reaches the target accurately as shown inFigure 8(b). For each step of the POP, the optimal δ that givesthe highest probability that the future path targets the goal isselected from a discrete set. We prepare two candidates asδ = α = 0.1 or δ = −α = −0.1. The selected parametersare σ = 0.02 in (2) and s = 20 for histogram smoothing.The angle θ in Figure 3 at the intermediate steps is obtainedin radian asθ : [0, 0.2, 0.4, 0.2, 0.4, 0.2, 0.4, 0.6, 0.4, 0.2].Note that these angles are generated from the pre-definedcandidate angular velocities (δ = −α or δ = α). With thesame parameters, the angle θ in Figure 3 for the intermediatesteps by the POP with the fuzzy is obtained in radian asθ : [0, 0.270, 0.515, 0.247, 0.430, 0.279, 0.320,

0.324, 0.326, 0.326].We can observe that each small path can be generated bycontinuous searching between candidates. The defuzzifica-tion for each step is shown in Figure 9 where the crisp valueis determined for δ.

Figure 10 shows the path generation by two methods withan obstacle. The circles denote the obstacles in Figure 10.As shown in Figure 10(a), the two wheeled robot cannotreach the goal close enough when the POP is applied. ThePOP with the fuzzy overcomes this limitation as shownFigure 10(b).

B. Flexible needle

For the flexible needle, we extend the tests to 3D space.The paths for the flexible needle obtained by the POP and

2982

−5

0

5 −5

0

50

5

10

YX

Z

(a)

−5

0

5 −5

0

50

5

10

YX

Z

(b)

Fig. 11. Path generation by POP and POP with fuzzy logic for the flexibleneedle

−5

0

5

−50

50

5

10

XY

Z

(a)

−5

0

5

−50

50

5

10

XY

Z

(b)

Fig. 12. Path generation with an obstacle by POP and POP with fuzzylogic for the flexible needle

the POP with the fuzzy are shown in Figure 11. For eachintermediate step, the optimal angular velocity ω0 around z-axis that gives the highest probability that the future pathtargets the goal position is selected. The selected parametersare λ = 0.1, s = 1.5 for Gaussian kernels, and thecurvature of the needle κ = 0.05. The path generated bythe POP is shown in Figure 11(a). The whole path does notreach the goal position accurately. With the same conditions,the path generated by the POP with the fuzzy is shownin Figure 11(b). Because each small path is generated bycontinuous searching, the result path is smoother and reachesthe target more accurately. In addition, Figure 12 confirmsthat when there is an obstacle in the needle insertion, theproposed method generates smoother and more accuratepath.

C. Method comparison

To compare the performances of the POP and the POPwith the fuzzy, we measure the targeting errors, the compu-tation time, and the path smoothness. The targeting errors,defined as distances between the last position of the systemand the goal, are shown in Table II. The POP with thefuzzy logic shows better performance in targeting the goalthan the POP method alone. Especially for the case withan obstacle, the proposed method can achieve significantlybetter performance.

As shown in Table III, the computational time is not prac-tically increased by adding the fuzzy logic. We confirmedthat the POP with a small number of candidates (2 candidatesfor the two wheeled robot and 3 candidates for the flexibleneedle) generates relatively non-smooth paths and sometimes

w/o obstacle w/ obstacle

The two wheeled robot POP 1.087 2.317POP-Fuzzy 0.453 0.624

The flexible needle POP 0.466 0.303POP-Fuzzy 0.119 0.111

TABLE IITARGETING ERRORS BY ALGORITHMS

fail to reach a goal as shown in Figures 8(a), 10(a), 11(a)and 12(a). The POP with the fuzzy logic spends almostthe same amount of time to generate the smoother pathsthat reliably reach to the goal. To generate paths that havesimilar smoothness using the POP method alone, we neededto use 7 and 36 candidates for the two wheeled robot andflexible needle, respectively, which results in the significantlyincreased computation time as shown in Table III.

w/o obstacle w/ obstacle

The two wheeled robotPOP 3.21s 3.07s

POP-Fuzzy 3.30s 3.18sPOP-s2* 10.85s 10.00s

The flexible needlePOP 49.68s 50.55s

POP-Fuzzy 49.78s 50.56sPOP-n2** 605.66s 609.78s

*POP-s2 : POP with 7 candidates for the smooth complete path.**POP-n2 : POP with 36 candidates for the smooth complete path.

TABLE IIICOMPUTATION TIME BY ALGORITHMS

To measure the smoothness of paths, we introduce twodefinitions to measure the roughness of the result path as

Rds =1

N

N∑i=1

|θi+1 − θi|2, (15)

Rσ =

√√√√ 1

N

N∑i=1

(di − µ)2. (16)

where N is the number of the angle (θ) changes in Figure 3,di is the difference between adjacent angles for the wholepath, and µ is mean of di. Table IV shows the roughnessresults obtained by (15) and (16).

Roughness by eq (15) Roughness by eq (16)POP POP-Fuzzy POP POP-Fuzzy

w/o obstacle 0.040 0.029 0.211 0.177w/ obstacle 0.040 0.032 0.200 0.184

TABLE IVROUGHNESS OF THE RESULTING PATHS FOR A TWO-WHEELED ROBOT

The results in Table IV verifies the proposed method cangenerate smoother paths than the POP method alone. Notethat the smoother paths have a smaller value of roughness.

V. CONCLUSIONS

A new approach to improve the performance of the POPalgorithm using the fuzzy logic was proposed. Althoughthe classical POP algorithm has been successfully used in

2983

path planning for robotic systems, this method used thediscrete search in the pre-defined possible path set. Dueto this limitation, the generated paths are not smooth andsometimes fail to reach a goal. The non-smooth referencepath may result in the extremely high input signal in dynamiccontrol. To overcome this, we modified the classical POPmethod by combining it with the fuzzy logic. Through thefuzzy logic approach, the discrete search could be replacedwith a continuous search. As a result, the new methodcould generate smooth paths that successfully reach to agoal. We confirmed the performance of the proposed methodusing the simulation. The two-wheeled robot and the flexibleneedle were used for the simulation. Only few candidatesfor intermediate paths (2 or 3) were enough in the test ofthe new method to generate the smooth paths. Using theroughness metrics we showed that the paths generated by thenew method were smoother than the results obtained by theprevious approach. It was also verified that the new methodcould generate paths that accurately hit the targets withoutsignificantly increasing the computation time. Based on thefreedom on the choice of membership functions in the fuzzylogic, we plan to find the optimal fuzzy membership functionto obtain better paths for robotics systems in the future.

REFERENCES

[1] P. White, V. Zykov, J. C. Bongard, and H. Lipson, “Three dimensionalstochastic reconfiguration of modular robots.” in Robotics: Science andSystems. Cambridge, 2005, pp. 161–168.

[2] S. K. Shah, C. D. Pahlajani, and H. G. Tanner, “Probability of successin stochastic robot navigation with state feedback,” in IntelligentRobots and Systems (IROS), 2011 IEEE/RSJ International Conferenceon. IEEE, 2011, pp. 3911–3916.

[3] K. J. Astrom, Introduction to stochastic control the-ory@Articlepark2008kinematic, Title = Kinematic state estimationand motion planning for stochastic nonholonomic systems using theexponential map, Author = Park, W. and Liu, Y. and Zhou, Y. andMoses, M. and others, Journal = Robotica, Year = 2008, Number =4, Pages = 419–434, Volume = 26, Publisher = Cambridge UniversityPress . Courier Dover Publications, 2012.

[4] I. Ebert-Uphoff and G. S. Chirikjian, “Inverse kinematics of discretelyactuated hyper-redundant manipulators using workspace densities,” inRobotics and Automation, 1996. Proceedings., 1996 IEEE Interna-tional Conference on, vol. 1. IEEE, 1996, pp. 139–145.

[5] W. Park, J. Kim, Y. Zhou, N. Cowan, A. Okamura, and G. Chirikjian,“Diffusion-based motion planning for a nonholonomic flexible needlemodel,” in Robotics and Automation, 2005. ICRA 2005. Proceedingsof the 2005 IEEE International Conference on. IEEE, 2005, pp.4600–4605.

[6] W. Park, Y. Liu, Y. Zhou, M. Moses, and G. Chirikjian, “Kinematicstate estimation and motion planning for stochastic nonholonomicsystems using the exponential map,” Robotica, vol. 26, no. 4, pp. 419–434, 2008.

[7] W. Park, Y. Wang, and G. Chirikjian, “The path-of-probability al-gorithm for steering and feedback control of flexible needles,” TheInternational Journal of Robotics Research, vol. 29, no. 7, p. 813,2010.

[8] J. Lee and W. Park, “Design and path planning for a sphericalrolling robot,” in International Mechanical Engineering Congress &Exposition. ASME, 2013, to appear.

[9] L. A. Zadeh, “Fuzzy sets,” Information and control, vol. 8, no. 3, pp.338–353, 1965.

[10] ——, “Is there a need for fuzzy logic?” Information Sciences, vol.178, no. 13, pp. 2751–2779, 2008.

[11] ——, “A new direction in fuzzy logic-toward a computational the-ory of perceptions,” in Fuzzy Information Processing Society, 1999.NAFIPS. 18th International Conference of the North American. IEEE,1999, pp. 1–4.

[12] ——, “A new direction in ai: Toward a computational theory ofperceptions,” AI magazine, vol. 22, no. 1, p. 73, 2001.

[13] L.-X. Wang and J. M. Mendel, “Fuzzy basis functions, universal ap-proximation, and orthogonal least-squares learning,” Neural Networks,IEEE Transactions on, vol. 3, no. 5, pp. 807–814, 1992.

[14] K. Zeng, N.-Y. Zhang, and W.-L. Xu, “A comparative study onsufficient conditions for takagi-sugeno fuzzy systems as universalapproximators,” Fuzzy Systems, IEEE Transactions on, vol. 8, no. 6,pp. 773–780, 2000.

[15] H. Ying, “General takagi-sugeno fuzzy systems are universal approx-imators,” in Fuzzy Systems Proceedings, 1998. IEEE World Congresson Computational Intelligence., The 1998 IEEE International Confer-ence on, vol. 1. IEEE, 1998, pp. 819–823.

[16] J. L. Castro, “Fuzzy logic controllers are universal approximators,”Systems, Man and Cybernetics, IEEE Transactions on, vol. 25, no. 4,pp. 629–635, 1995.

[17] B. Kosko, “Fuzzy systems as universal approximators,” Computers,IEEE Transactions on, vol. 43, no. 11, pp. 1329–1333, 1994.

[18] D. Higham, “An algorithmic introduction to numerical simulation ofstochastic differential equations,” SIAM review, pp. 525–546, 2001.

[19] L. E. Dubins, “On curves of minimal length with a constraint onaverage curvature, and with prescribed initial and terminal positionsand tangents,” American Journal of mathematics, pp. 497–516, 1957.

[20] T. Fraichard, “Smooth trajectory planning for a car in a structuredworld,” in Robotics and Automation, 1991. Proceedings., 1991 IEEEInternational Conference on. IEEE, 1991, pp. 318–323.

[21] E. P. Anderson, R. W. Beard, and T. W. McLain, “Real-time dynamictrajectory smoothing for unmanned air vehicles,” Control SystemsTechnology, IEEE Transactions on, vol. 13, no. 3, pp. 471–477, 2005.

[22] L. Fu, A. Yazici, and U. Ozguner, “Route planning for osu-actautonomous vehicle in darpa urban challenge,” in Intelligent VehiclesSymposium, 2008 IEEE. IEEE, 2008, pp. 781–786.

[23] J.-H. Wei and J.-S. Liu, “Collision-free composite? 3–splines gener-ation for nonholonomic mobile robots by parallel variable-length ge-netic algorithm,” in Computational Intelligence for Modelling Control& Automation, 2008 International Conference on. IEEE, 2008, pp.545–550.

[24] J.-w. Choi, R. Curry, and G. Elkaim, “Path planning based onbezier curve for autonomous ground vehicles,” in World Congress onEngineering and Computer Science 2008, WCECS’08. Advances inElectrical and Electronics Engineering-IAENG Special Edition of the.IEEE, 2008, pp. 158–166.

[25] K. Yang and S. Sukkarieh, “An analytical continuous-curvature path-smoothing algorithm,” Robotics, IEEE Transactions on, vol. 26, no. 3,pp. 561–568, 2010.

[26] E. Magid, D. Keren, E. Rivlin, and I. Yavneh, “Spline-based robotnavigation,” in Intelligent Robots and Systems, 2006 IEEE/RSJ Inter-national Conference on. IEEE, 2006, pp. 2296–2301.

[27] A. Piazzi, C. G. L. Bianco, and M. Romano, “-splines for thesmooth path generation of wheeled mobile robots,” Robotics, IEEETransactions on, vol. 23, no. 5, pp. 1089–1095, 2007.

[28] Y.-J. Ho and J.-S. Liu, “Collision-free curvature-bounded smooth pathplanning using composite bezier curve based on voronoi diagram,” inComputational Intelligence in Robotics and Automation (CIRA), 2009IEEE International Symposium on. IEEE, 2009, pp. 463–468.

[29] M. Pivtoraiko, R. A. Knepper, and A. Kelly, “Differentially constrainedmobile robot motion planning in state lattices,” Journal of FieldRobotics, vol. 26, no. 3, pp. 308–333, 2009.

[30] S. On and A. Yazici, “A comparative study of smooth path planningfor a mobile robot considering kinematic constraints,” in Innovationsin Intelligent Systems and Applications (INISTA), 2011 InternationalSymposium on. IEEE, 2011, pp. 565–569.

[31] Y. Zhou and G. S. Chirikjian, “Nonholonomic motion planning usingdiffusion of workspace density functions,” in ASME 2003 InternationalMechanical Engineering Congress and Exposition. ASME, 2003.

[32] W. Park, Y. Wang, and G. S. Chirikjian, “Path planning for flexibleneedles using second order error propagation,” in Algorithmic Foun-dation of Robotics VIII. Springer, 2009, pp. 583–595.

[33] R. J. Webster, J. S. Kim, N. J. Cowan, G. S. Chirikjian, and A. M.Okamura, “Nonholonomic modeling of needle steering,” The Interna-tional Journal of Robotics Research, vol. 25, no. 5-6, pp. 509–525,2006.

2984