Autonomous Perpendicular And Parallel Parking Using Multi ...

7
Autonomous Perpendicular And Parallel Parking Using Multi-Sensor Based Control* David P´ erez-Morales 1 , Olivier Kermorgant 1 , Salvador Dom´ ınguez-Quijada 1 and Philippe Martinet 1 Abstract— This paper addresses the perpendicular and par- allel parking problems of car-like vehicles for both forward and reverse maneuvers in one trial by improving the work presented in [1] using a multi sensor based controller with a weighted control scheme. The perception problem is discussed briefly considering a Velodyne VLP-16 and a SICK LMS151 as the sensors providing the required exteroceptive information. The results obtained from simulations and real experimentation for different parking scenarios show the validity and potential of the proposed approach. I. I NTRODUCTION Even for experienced drivers, parking can be a difficult task, especially in big cities were the parking spots are often very narrow. The search for an increase in comfort and safety when parking has lead to a quite extensive literature [2], having explored many different approaches to automate this bothersome task. Despite the fact that the automobile industry has already started to roll out some commercial implementations of active parking assistants capable of actively controlling ac- celeration, breaking and steering [3], the research interest in the topic remains strong. Path planning approaches have been heavily investigated in recent years. Among the different planning techniques it is possible to distinguish between geometric approaches, with either constant turning radius [4], [5] using saturated feedback controllers, or continuous-curvature planning using clothoids [6]; heuristic approaches [7] and machine learning techniques [8]. It is worth to note that parking maneuvers with forward motions are seldom considered, with [9] for the parallel parking case and [10] for the perpendicular case being some of the few works on this regard. A well known drawback of path planning and tracking is its dependence on the localization performance. An interest- ing alternative that does not rely on the localization is the use of a sensor based control approach. It has been proven to be valid for navigation [11], dynamic obstacles avoidance [12], and for parking applications [1]. *This work was supported by the Mexican National Council for Science and Technology (CONACYT). This paper describes work carried out in the framework of the Valet project, reference ANR-15-CE22-0013-02. 1 David erez-Morales, Olivier Kermorgant, Salvador Dom´ ınguez- Quijada and Philippe Martinet are with LS2N, Laboratoire des Sciences du Num´ erique de Nantes, ´ Ecole Centrale de Nantes, 1 rue de la No¨ e, 44321 Nantes, France 1 [email protected] 1 [email protected] 1 [email protected] 1 [email protected] The contribution of this paper is an improvement on the approach described in [1], this time considering multiple sensors, a better suited sensor feature set that allows to park in one maneuver not only in perpendicular spots but also in parallel ones with either reverse or forward motions with only some minor changes, and improved constraints for collision avoidance. In the next section the models considered as well as the notation used are presented. In Section III the perception problem is briefly addressed showing how the sensor data is processed in order to extract the empty parking spot to latter in Section IV describe the interaction model and how to extract the required sensor features from the computed empty parking spot. Afterwards, the controller is presented in Section V and the obtained results from simulation and real experimentation for different parking scenarios are shown in Section VI. Finally, some conclusions are given in Sec- tion VII. II. MODELING AND NOTATION Given that parking maneuvers are low speed motions, a kinematic model can be considered as accurate enough. A. Car-like robot model and notation The kinematic model considered is the one used to repre- sent a car with rear-wheel driving: ˙ x ˙ y ˙ θ ˙ φ = cos θ sin θ tan φ/l wb 0 v + 0 0 0 1 ˙ φ, (1) where v and ˙ φ are the longitudinal and steering velocities. Table I presents the different parameters used in the paper. TABLE I: Parameters definition Parameteres Notation Value Wheelbase: Distance between the front and rear wheel axles l wb 2.588 m Rear overhang: Distance between the rear wheel axle and the rear bumper lro 0.657 m Maximum steering angle φmax 30 Total length of the vehicle lve 4.084 m Total width of the vehicle wve 1.945 m Maximum (desired) longitudinal ve- locity |vmax| 2 km/h Maximum acceleration increment Δacc sign(v)0.2 Ts Maximum deceleration increment Δ dec sign(v)2.5 Ts Maximum φ increment Δ φ 2 Ts The point M is located at the mid-distance between the passive fixed wheels (rear) axle and the distance between the

Transcript of Autonomous Perpendicular And Parallel Parking Using Multi ...

Page 1: Autonomous Perpendicular And Parallel Parking Using Multi ...

Autonomous Perpendicular And Parallel ParkingUsing Multi-Sensor Based Control*

David Perez-Morales1, Olivier Kermorgant1, Salvador Domınguez-Quijada1 and Philippe Martinet1

Abstract— This paper addresses the perpendicular and par-allel parking problems of car-like vehicles for both forwardand reverse maneuvers in one trial by improving the workpresented in [1] using a multi sensor based controller with aweighted control scheme. The perception problem is discussedbriefly considering a Velodyne VLP-16 and a SICK LMS151 asthe sensors providing the required exteroceptive information.The results obtained from simulations and real experimentationfor different parking scenarios show the validity and potentialof the proposed approach.

I. INTRODUCTION

Even for experienced drivers, parking can be a difficulttask, especially in big cities were the parking spots are oftenvery narrow. The search for an increase in comfort and safetywhen parking has lead to a quite extensive literature [2],having explored many different approaches to automate thisbothersome task.

Despite the fact that the automobile industry has alreadystarted to roll out some commercial implementations ofactive parking assistants capable of actively controlling ac-celeration, breaking and steering [3], the research interest inthe topic remains strong.

Path planning approaches have been heavily investigatedin recent years. Among the different planning techniquesit is possible to distinguish between geometric approaches,with either constant turning radius [4], [5] using saturatedfeedback controllers, or continuous-curvature planning usingclothoids [6]; heuristic approaches [7] and machine learningtechniques [8]. It is worth to note that parking maneuverswith forward motions are seldom considered, with [9] forthe parallel parking case and [10] for the perpendicular casebeing some of the few works on this regard.

A well known drawback of path planning and tracking isits dependence on the localization performance. An interest-ing alternative that does not rely on the localization is theuse of a sensor based control approach. It has been provento be valid for navigation [11], dynamic obstacles avoidance[12], and for parking applications [1].

*This work was supported by the Mexican National Council for Scienceand Technology (CONACYT). This paper describes work carried out in theframework of the Valet project, reference ANR-15-CE22-0013-02.

1 David Perez-Morales, Olivier Kermorgant, Salvador Domınguez-Quijada and Philippe Martinet are with LS2N, Laboratoire des Sciences duNumerique de Nantes, Ecole Centrale de Nantes, 1 rue de la Noe, 44321Nantes, France

1 [email protected] [email protected] [email protected] [email protected]

The contribution of this paper is an improvement on theapproach described in [1], this time considering multiplesensors, a better suited sensor feature set that allows to parkin one maneuver not only in perpendicular spots but also inparallel ones with either reverse or forward motions with onlysome minor changes, and improved constraints for collisionavoidance.

In the next section the models considered as well as thenotation used are presented. In Section III the perceptionproblem is briefly addressed showing how the sensor datais processed in order to extract the empty parking spot tolatter in Section IV describe the interaction model and howto extract the required sensor features from the computedempty parking spot. Afterwards, the controller is presented inSection V and the obtained results from simulation and realexperimentation for different parking scenarios are shownin Section VI. Finally, some conclusions are given in Sec-tion VII.

II. MODELING AND NOTATION

Given that parking maneuvers are low speed motions, akinematic model can be considered as accurate enough.

A. Car-like robot model and notation

The kinematic model considered is the one used to repre-sent a car with rear-wheel driving:

xy

θ

φ

=

cos θsin θ

tanφ/lwb0

v +

0001

φ, (1)

where v and φ are the longitudinal and steering velocities.Table I presents the different parameters used in the paper.

TABLE I: Parameters definition

Parameteres Notation ValueWheelbase: Distance between thefront and rear wheel axles

lwb 2.588 m

Rear overhang: Distance between therear wheel axle and the rear bumper

lro 0.657 m

Maximum steering angle φmax 30◦

Total length of the vehicle lve 4.084 mTotal width of the vehicle wve 1.945 mMaximum (desired) longitudinal ve-locity

|vmax| 2 km/h

Maximum acceleration increment ∆acc sign(v) 0.2 TsMaximum deceleration increment ∆dec sign(v) 2.5 TsMaximum φ increment ∆φ 2◦ Ts

The point M is located at the mid-distance between thepassive fixed wheels (rear) axle and the distance between the

Page 2: Autonomous Perpendicular And Parallel Parking Using Multi ...

rear and the front axle is described by lwb. The generalizedcoordinates are q = [x, y, θ, φ]T where x and y are theCartesian coordinates of the point M, θ is the orientationof the platform with respect to the x0 axis and the steeringangle of the steerable wheel(s) is described by φ (Fig. 1a).

From the kinematic model it is possible to extract thefollowing relation between φ and θ:

φ = atan(θ lwbv

) (2)

The vehicle used for experimentation and simulation isa Renault ZOE (Fig. 1b). It is represented by its boundingrectangle.

x0

y0 ϕ

y m

x m

lwb

ltr

lfo

lro

lls

lrs

θMy

x

(a) Kinematic model diagram (b) Robotized Renault ZOE

Fig. 1: Kinematic model diagram for a car-like rear-wheeldriving robot and vehicle used for simulation and realexperimentation

B. Multi-sensor modeling

Following our previous work [1], where a novel sensorbased control technique based on the framework described in[13] was proposed, in this paper we explore a different sensorfeatures set to park in one maneuver into perpendicular andparallel spots considering multiple sources for the sensorsignals.

1) Kinematic model: Let us consider a robotic systemequipped with k sensors (Fig. 2) that provide data about therobot pose in its environment. Each sensor Si gives a signal(sensor feature) si of dimension di with

∑ki=1 di = d.

F0

Fm

F1

F2 FO

S1

S2control frame

Object ofinterest

objectframe

1Wm

2Wm

5 10 15 20 25 30 35 40 45

-6

-4

-2

0

2

4

5 10 15 20 25 30 35 40 45

-6

-4

-2

0

2

4

sensorsignal

sensorsignal

Fig. 2: Multi-sensor model

In a static environment, the sensor feature derivative canbe expressed as follows:

si = Livi = LiiWmvm (3)

where Li is the interaction matrix of si and iWm is the screwtransformation matrix that allows to express the sensor twistvi with respect to the robot twist vm.

Assuming that the vehicle to which the sensors are rigidlyattached to evolves in a plane and that the sensors and vehiclehave vertical parallel z axes, Li is of dimension di × 3 andthe screw transformation matrix takes the following form:

iWm =

c (mθi) s (mθi) tix s (mθi)− tiy c (mθi)

−s (mθi) c (mθi) tix c (mθi) + tiy s (mθi)

0 0 1

(4)

where mti = [tix , tiy ]T and mθi are, respectively, theposition and orientation of Si with respect to Fm expressedin Fm, with c (mθi) = cos (mθi) and s (mθi) = sin (mθi).

Denoting s = (s1, . . . , sk) the d-dimensional signal of themulti-sensor system, the signal variation over time can belinked to the moving vehicle twist:

s = Lsvm (5)

with:

Ls = LWm =

L1 . . . 0...

. . ....

0 . . . Lk

1Wm

...kWm

(6)

Nevertheless, since in our application the control frameFm is attached to the vehicle’s rear axis with origin at theM point (Fig. 1a), it is not possible to generate a velocityalong ym on the vehicle’s frame due to the nonholonomicconstraint of the kinematic model (1). Assuming that thereis no slipping nor skidding (i.e. vym = 0), the robot twistvm = [vxm , vym , θ]

T can be reduced to:

vm = [vxm, θ]T (7)

where vxm= v and considering as well the consequent

reduction of Ls, being now of dimension d× 2.2) Weighted error: We consider the weighted multi-sensor

error signal, as described in [13], which is defined as:

eH = He (8)

where e = s − s∗ is the difference between the currentsensor signal s and its desired value s∗ and H is a diagonalpositive semi-definite weighting matrix that depends on swith its associated interaction matrix being LH = HLs.Making a distinction between task and constraints features,H = diag(Ht,Hc) and s = [st, sc]

T . Each component hiof H may or may not vary in order to optimize the systembehavior, ensure specific constraints, manage priorities or addor remove a sensor or a feature from the control law.

Task features st, as their name suggest, are used to performthe task by driving et to 0. On the other hand, sincethe constraints features sc are used only to ensure certainconstraints, we don’t care about ec as the desired value s∗cis meaningless.

Page 3: Autonomous Perpendicular And Parallel Parking Using Multi ...

III. PERCEPTION

We focus the perception on the detection of parked cars.They can be approximated by boxes considering that, whenviewed from the top, have a rectangular-like shape.

The vehicle used (Fig. 1b) has been equipped with manysensors (Velodyne VLP-16, SICK LMS151, GPS, camerasin the front, etc.) to observe its environment, a computerto process the data and actuators that can be computercontrolled. Since our application requires exteroceptive in-formation from all around the vehicle at, potentially closedistances, the VLP-16 and SICK LMS151 were the sensorschosen to work with.

Because both sensors provide information of a very similarnature, the data can be fused by simply converting theLaserScan data provided by the LMS151 to PointCloud2 andthen transforming the point cloud from LMS151’s frame tothe VLP-16’s frame so it can be added to the point cloudprovided by the latter sensor. For this, it is assumed that thetime difference between the data provided by each sensor isreasonably small, i.e. the data is sufficiently synchronized.

The complete point cloud obtained from the two sensorsis first filtered with a couple of crop boxes. The first cropbox is keeps only the data that is close enough to thecar to be relevant in a parking application and that doesnot represent the floor and afterwards and the second oneis used to filter out the points that belong to the car’sbody (self-collision sensor readings). Then, an EuclideanCluster Extraction algorithm is used to have each obstaclerepresented as a cluster. The orientation of each cluster isextracted by fitting a line model to the points belongingto the contour of the cluster using a RANSAC algorithm.The orientation of the bounding box will be equal to theorientation of the fitted line. After, we proceed by findingthe rotated bounding box of the cluster using the previouslyfound orientation.

The empty parking place (green rectangle in Fig. 3) isextracted using the approach described in [1]. The sensorfeatures required for the controller are extracted from thiscomputed parking place.

IV. INTERACTION MODEL

For the interaction model, we rely on the perception ofseveral lines Lj and points from several sensors. Since thesensor data is expressed in the Cartesian space, it can beeasily transformed from one frame to another, thus allowingus to use virtual sensors placed at will.

The sensor’s placement can be seen in Fig. 3. S1 corre-sponds to the VLP-16 while S2 to the LMS151. S3 to S5 arevirtual sensors placed on the corners of the car’s boundingrectangle. All the frames of the virtual sensors have the sameorientation as the control frame.

To illustrate the feature extraction approach, the case ofa reverse perpendicular maneuver is now detailed. As it canbe seen in Fig. 3, points p1 to p4 correspond to the cornersof the parking spot while p5 and p6 are, respectively, themidpoints between (p1, p4) and (p2, p3). L1 is a line thatpasses through p5 and p6, i.e. it passes through the center

of the parking spot. L2 is a line that passes through p1 andp4 thus corresponding to the depth limit of the parking spot.L3 is a line that passes through p3 and p4. All the lines areparametrized using normalized Plucker coordinates.

Fig. 3: Sensors’ configuration and sensor features

The exact definition of the sensor features varies depend-ing on the parking scenario although in any case, L∗1 shouldbe collinear with xm and L∗2 should be parallel to ym and bebehind the car for reverse maneuvers and in front for forwardones. In this paper we only detail the actual features usedfor a specific case, but deducing the features that should beused for other cases isn’t complicated.

Considering the previously mentioned assumption that thevehicle to which the sensors are attached to evolves in a plane(sensors and vehicle with parallel z axes), the sensor signalsiLj and interaction matrix LiLj for the line Lj observed bySi are defined respectively by (9) and (10)

siLj =[iuj(1), iuj(2), ihj(3)

]T(9)

LiLj =

0 0 iuj(2)0 0 −iuj(1)

−iuj(2) iuj(1) 0

(10)

where iuj = iuj/||iuj || with iuj 6= 0 denoting theorientation of Lj and ihj = iwj/||iuj || with iwj containingthe coefficients of the interpretation plane equation [14]. Inthe 2D configuration considered, the components of iuj andihj that don’t appear in (9) are equal to 0 thus ihj(3) canbe interpreted as the distance to the line.

It should be noted that the weighting and constraintsrequired to park safely change depending on the type ofparking spot (parallel, perpendicular or diagonal) and onwhich side the parking spot is placed with respect to thecar at the beginning of the maneuver.

A. Task sensor featuresThe control features required to perform the parking task

are defined by (11), with t = 1 for forward maneuvers andt = 2 for the reverse case.

st = [stL1 , stL2 ]T (11)

A 2nd order approximation of the form (12) is used forthe interaction matrix.

Lt =LLj + L∗Lj

2(12)

Page 4: Autonomous Perpendicular And Parallel Parking Using Multi ...

The weighting matrix Ht is defined by (13). The variablecomponents hti are computed using a smooth weightingfunction (Fig. 4) based on the one presented in [15].

Ht = diag(ht1, ht2, h

tconst3 , ht4, h

t5, h

tconst6 ) (13)

s- ss- ss+ s+hi-

hi+

Fig. 4: Weighting function hti

With this weighting function and considering the weight-ing parameters (31), si ∀ i = {2, 4, 5} could be seen asbounded constraints but in fact they are task features, giventhat we do care about the value of their corresponding ei.If only s3 and s6 were considered as task features, thecar may finish the maneuver with a bad orientation evenif e3 ≈ e6 ≈ 0 because just 2 features are not enough tocontrol the car’s DOFs.

Due to space constraints, only the case of a reverseperpendicular parking maneuver with the spot placed on theright will be considered for the rest of this section.

B. Constraints sensor featuresThe constraints are defined by (14).

sc = [s3, s4, s5]T (14)

For the constraints sensor features we are interested onlyin the components of (9) related to the distance to the featureitself, therefore:

s3 = 3h3(3) (15)

s4 = [4h2(3), 4h3(3)]T (16)

s5 = [5h2(3), 5dym ]T (17)

with 5dym being the difference dym = ρcorner − ρlatmeasured with the sensor S5, expressed in the sensor frame(Fig. 5) if φ < 0, defined as:

5dym =

√(5x2 + t5x)

2+(5y2 + t5y − ρm

)2+ ρm − t5y

(18)with ρm = lwb/tanφ and, when φ ≥ 0, being simply thedistance from S5 to p2 along ym measured with S5, it isdefined as:

5dym = 5y2 (19)

with 5p2 = (5x2,5y2) being the point p2 measured with S5.

The corresponding interaction matrices are:

L3 =[−3u3(2) 3u3(1) 0

](20)

L4 =

[−4u2(2) 4u2(1) 0−4u3(2) 4u3(1) 0

](21)

L5 =

[−5u2(2) 5u2(1) 0

0 −1 −5x2

](22)

Since the constraints are used for collision avoidance, onlyone side of the interval [s−c , s

+c ] (25) has to be defined for

each feature.

Fig. 5: Lateral constraint d

V. CONTROL

When considering the constraints presented in Sec. IV-B (particularly (18)), a chattering problem appears if thecontroller presented in [1] is used, even with very smallweights. For this reason, that controller had to be adapted tothe quadratic programming form [16] with only inequalityconstraints (23):

vm = argmin||LHt.vm + λ.et||2

s.t. Avm ≤ b(23)

with:A = [LHc

,−LHc]T (24)

b = [α(s+c − sc),−α(s−c − sc)]T (25)

where α is a gain constant, λ is the control gain, Hc is anidentity matrix (i.e. there is no weighting on the constraints)and [s−c , s

+c ] is the interval in which we want to keep sc.

To limit the speed of the vehicle as it approaches to theparking spot, a deceleration profile, based on the velocityprofile shown in [5], is used. It is defined by (26)

if e(6) < e(6)th

vmax = (|vmax| − v0max)(e(6)/e(6)th) + v0max(26)

with v0max being the maximum desired velocity when thesixth component of the error vector e(6) tends to zero ande(6)th is a threshold value for e(6). Since the low levelvelocity controller is not capable of reaching very smallvalues, v0max = 0.2 km/h.

The control signals v and φ are bounded by their respectivemaximum desired values as shown below:

|v| < |vmax| (27)

|φ| < φmax (28)

To avoid large changes in the control signals at time k thatmay cause uncomfortable sensations for the passengers orsurrounding witnesses, they are bounded by some increments(29) (30) with respect to the control signal at k − 1.

(vk−1 −∆dec) ≥ vk ≤ (vk−1 + ∆acc) (29)

(φk−1 −∆φ) ≥ φk ≤ (φk−1 + ∆φ) (30)

Page 5: Autonomous Perpendicular And Parallel Parking Using Multi ...

To solve (23), a generic solver is used. To improve thestability and computation time, the optimization variablesare [v, φ] and not vm, although inside the objective functionθ is computed from φ so (23) can be solved. When usingφ instead of θ one can easily impose the bounds (28) atthe solving step instead of solving (23) directly with vm asoptimization variables and hope for the value of φ computedfrom θ to fall inside the bounds (28).

VI. RESULTS

To show the potential of our approach, several parkingscenarios are presented below, all of them using the finalform of the controller (23). The unconstrained cases werecomputed in MATLAB, using fmincon as solver. For theconstrained cases, NLopt with the SLSQP algorithm wasused.

A. Unconstrained cases - MATLAB

To evaluate the performance of the proposed approach, itwas first tested in unconstrained cases with a sampling timeTs = 0.1. As it can be seen in Figs. 6-10, the presentedtechnique allows to perform parking maneuvers for manydifferent scenarios (perpendicular and parallel with eitherreverse or forward motions) just by adjusting the weightingparameters and the specific definition of the sensor features.The final errors for all of these cases are in the order of×10−3 or smaller.

As an example of the weighting approach, for the case ofa reverse perpendicular parking maneuver with the parkingspot placed on the right, h+i = 5, h−i = 0, htconst

3 = 1,htconst6 = 0.75 and:

ss+

1 = s+1 =∞ss−

1 = 0.001 + s∗1

s−1 = −0.001 + s∗1

ss−

i = s−i = −∞ ∀ i = {2, 4, 5}ss

+

i = −0.001 + s∗i ∀ i = {2, 4, 5}s+i = 0.001 + s∗i ∀ i = {2, 4, 5}

(31)

These weighting parameters allow to prioritize the errorin position over the orientation for the most part of themaneuver and, when iu

∗j (a) is almost reached, smoothly

increase the corresponding weights so we can graduallyswitch the priority from positioning the vehicle to orientateit to avoid finishing the maneuver with a bad orientation.

It can be seen how, for all shown cases, the weights (Figs.6d-10d) push φ towards 0 (Figs. 6b-10b) once iu

∗j (a) is

almost reached when close to the completion of the maneuverto keep the orientation close to the desired value.

Unlike our previous work [1], which required to performgain-tunning for different initial conditions, this newly pre-sented approach allows to park successfully for different(reasonable) initial positions and orientations of the sameparking case using the same weighting parameters, althoughit should be mentioned that the stability, specially whenconstraints are considered, is still under study.

In Fig. 10, it can be seen how even if the car is placedconsiderably farther from the parking spot than in Fig. 6 andnot exactly perpendicular to the spot, the vehicle is able topark correctly using the same weighting parameters, showingthe stability of the presented approach.

-2 0 2 4 6 8 10-2

0

2

4

6

8

10Parking maneuver evolution

(a) Performed maneuver

time0 5 10 15 20 25 30 35

-2

-1

0Linear velocity evolution (km/h)

time0 5 10 15 20 25 30 35

-40

-20

0Steering angle evolution (degs)

(b) Control signals

time0 5 10 15 20 25 30 35

-5

0

5

10Task errors

e1

e2

e3

e4

e5

e6

(c) Task error signaltime

0 5 10 15 20 25 30 350

1

2

3

4Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(d) Task features’ weights

Fig. 6: Unconstrained perpendicular reverse parking maneu-ver

-8 -6 -4 -2 0 2 4-2

0

2

4

6

8

10Parking maneuver evolution

(a) Performed maneuver

time0 5 10 15 20 25 30 35

0

1

2Linear velocity evolution (km/h)

time0 5 10 15 20 25 30 35

-40

-20

0Steering angle evolution (degs)

(b) Control signals

time0 5 10 15 20 25 30 35

-8

-6

-4

-2

0

2

4Task errors

e1

e2

e3

e4

e5

e6

(c) Task error signaltime

0 5 10 15 20 25 30 350

0.5

1

1.5

2

2.5

3Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(d) Task features’ weights

Fig. 7: Unconstrained perpendicular forward parking maneu-ver

B. Constrained cases1) Fast prototyping environment: A homemade fast pro-

totyping environment using the same software architectureas the one embedded inside the car is used for simulationpurposes. This homemade environment is interfaced withGazebo to simulate the exteroceptive sensors.

The case of a reverse perpendicular parking maneuver withthe spot placed on the right is shown below. The weightingparameters remain the same as for the unconstrained casewhile the constraints are defined with s+7 = −0.1, s−8 =0.15, s+9 = −0.1, s−10 = 0.15, s+11 = −0.075 and Ts = 0.05.

Page 6: Autonomous Perpendicular And Parallel Parking Using Multi ...

-2 0 2 4 6 8 10 12-4

-2

0

2

4

6

8Parking maneuver evolution

(a) Performed maneuver

time0 5 10 15 20 25 30 35

-2

-1

0Linear velocity evolution (km/h)

time0 5 10 15 20 25 30 35

-40

0

40Steering angle evolution (degs)

(b) Control signals

time0 5 10 15 20 25 30 35

-8

-6

-4

-2

0

2

4Task errors

e1

e2

e3

e4

e5

e6

(c) Task error signaltime

0 5 10 15 20 25 30 350

1

2

3

4Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(d) Task features’ weights

Fig. 8: Unconstrained parallel reverse parking maneuver

-8 -6 -4 -2 0 2 4-4

-2

0

2

4

6

8Parking maneuver evolution

(a) Performed maneuver

time0 5 10 15 20 25 30 35

0

1

2Linear velocity evolution (km/h)

time0 5 10 15 20 25 30 35

-40

0

40Steering angle evolution (degs)

(b) Control signals

time0 5 10 15 20 25 30 35

-2

0

2

4

6

8Task errors

e1

e2

e3

e4

e5

e6

(c) Task error signaltime

0 5 10 15 20 25 30 350

1

2

3

4

5Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(d) Task features’ weights

Fig. 9: Unconstrained parallel forward parking maneuver

-2 0 2 4 6 8 10 12

-2

0

2

4

6

8

10

Parking maneuver evolution

(a) Performed maneuver

time0 5 10 15 20 25 30 35

-2

-1

0Linear velocity evolution (km/h)

time0 5 10 15 20 25 30 35

-40

0

40Steering angle evolution (degs)

(b) Control signals

time0 5 10 15 20 25 30 35

-5

0

5

10Task errors e

1

e2

e3

e4

e5

e6

(c) Task error signaltime

0 5 10 15 20 25 30 350

1

2

3

4Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(d) Task features’ weights

Fig. 10: Unconstrained perpendicular reverse parking maneu-ver from far

As it can be seen in Figs. 11-12, the car is able topark successfully while respecting the constraints in spite ofthe sensor noise and the less than perfect system response.The evolution of the many different signals, especiallyfor the longitudinal velocity (Fig. 12a), is very similarto the unconstrained case (Fig. 6b). The fast decelerationat the end (Fig. 12a) is due to a stopping condition inthe implementation related to et. Regarding the evolutionof φ, it can be seen how, contrary to the unconstrainedcase, it doesn’t saturate; this behavior is caused by theconstraints, particularly s11 (Fig. 12d). The final error is et =[−0.0003,−0.0096, 0.0207,−0.0096, 0.0003, 0.0569]T .

Fig. 11: Constrained perpendicular reverse parking maneuver

time0 5 10 15 20 25

-2

-1

0Linear velocity evolution (km/h)

controlresponse

time0 5 10 15 20 25

-30-20-10

0

Steering angle evolution (degs)

controlresponse

(a) Control signalstime

0 5 10 15 20 25-5

0

5

10Task errors

e1

e2

e3

e4

e5

e6

(b) Task error signal

time0 5 10 15 20 25

0

1

2

3

4

5Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(c) Task features’ weightstime

0 5 10 15 20 25-10

-5

0

5

10Constraints sensor signals s

7

s8

s9

s10

s11

(d) Constraints sensor signals

Fig. 12: Constrained perpendicular reverse parking maneuversignals

2) Real experimentation: Real experimentation was con-ducted for the same parking case (Fig. 13) as with thefast prototyping environment shown above. The weightingparameters and constraints definition remain the same.

Fig. 13: Experimental car parking in a perpendicular spot

It is obvious that the response of the system, particularlyfor the linear velocity (Fig. 14a), is less than ideal, reaching

Page 7: Autonomous Perpendicular And Parallel Parking Using Multi ...

time0 5 10 15

-4

-2

0Linear velocity evolution (km/h)

controlresponse

time0 5 10 15

-20

0

20

Steering angle evolution (degs)

controlresponse

(a) Control signalstime

0 5 10 15

-4

-2

0

2

4

6

Task errors e1

e2

e3

e4

e5

e6

(b) Task error signal

time0 5 10 15

0

1

2

3

4

5Task weights

ht1

ht2

htconst3

ht4

ht5

htconst6

(c) Task features’ weightstime

0 5 10 15-10

-5

0

5

10Constraints sensor signals s

7

s8

s9

s10

s11

(d) Constraints sensor signals

Fig. 14: Constrained perpendicular reverse parking maneuversignals

a speed more than twice as fast than what the controllerindicates. This behavior can be attributed to the low-levelvelocity controller, which still requires some tunning toimprove the performance at low velocities, therefore it hasno relation to the presented technique.

Despite of the erratic response of the system in additionto the noise coming from the sensors, the constraints wererespected during the whole maneuver (Fig. 14d), getting nocloser than 33.88cm (s9) to L3.

Furthermore, the evolution of et (Fig. 14b) is verysimilar to the simulated case (Fig. 12b), although thefinal error is not as good, being in this case et =[0.0054, 0.0743,−0.1436, 0.0743,−0.0054,−0.0833]T .

The smallest ||et|| was achieved at T = 12.6399s, withet = [0.0025, 0.0429,−0.0851, 0.0429,−0.0025, 0.0207]T

and [v, φ]T = [0, 0]T from the controller starting at T =12.42s.

VII. CONCLUSIONS

Following our previous work [1], we showed how a betterchoice of the sensor features allows to improve the perfor-mance, stability and versatility of the presented sensor basedapproach, this time not only being able to deal successfullywith perpendicular parking maneuvers but also with parallelones with both reverse and forward motions with just someminor adjustments for each type of parking. The stability,specially when constraints are considered, is still under study.

Preliminary results obtained from real experimentationvalidate the robustness and effectiveness of the presentedapproach, considering that, despite of the erratic response ofthe system due to the low-level velocity controller, the carparked successfully while respecting the constraints duringthe whole maneuver.

It is important to mention that, due to visibility constraintsand in order to keep the results obtained with the fast

prototyping environment as close to the reality as possible,only reverse parking maneuvers have been tested outsideMATLAB with the presented sensor feature set. Neverthe-less, the multi-sensor framework gives a high expandability,allowing for future upgrades to the perception capabilities ofthe system.

REFERENCES

[1] D. Perez Morales, S. Domınguez Quijada, O. Kermorgant, and P. Mar-tinet, “Autonomous parking using a sensor based approach,” in 8thWorkshop on Planning, Perception and Navigation for IntelligentVehicles, PPNIV’16 at 19th IEEE ITSC 2016, Rio de Janeiro, Brazil,2016, pp. 211–216.

[2] W. Wang, Y. Song, J. Zhang, and H. Deng, “Automatic parking ofvehicles: A review of literatures,” International Journal of AutomotiveTechnology, vol. 15, no. 6, pp. 967–978, 2014.

[3] Y. Song and C. Liao, “Analysis and Review of State-of-the-Art Auto-matic Parking Assist System,” in 2016 IEEE International Conferenceon Vehicular Electronics and Safety, Beijing, China, 2016, pp. 61–66.

[4] P. Petrov, F. Nashashibi, and M. Marouf, “Path Planning and Steeringcontrol for an Automatic Perpendicular Parking Assist System,” in7th Workshop on Planning, Perception and Navigation for IntelligentVehicles, PPNIV’15, Hamburg, Germany, 2015, pp. 143–148.

[5] P. Petrov and F. Nashashibi, “Saturated Feedback Control for anAutomated Parallel Parking Assist System,” in 13th International Con-ference on Control, Automation, Robotics and Vision (ICARCV’14),Marina Bay Sands, Singapore, 2014, pp. 577–582.

[6] H. Vorobieva, N. Minoiu-Enache, S. Glaser, and S. Mammar, “Ge-ometric Continuous-Curvature Path Planning for Automatic ParallelParking,” in 2013 10th IEEE International Conference on Networking,Sensing and Control (ICNSC), Evry, France, 2013, pp. 418–423.

[7] C. Chen, M. Rickert, and A. Knoll, “Path planning with orientation-aware space exploration guided heuristic search for autonomous park-ing and maneuvering,” in 2015 IEEE Intelligent Vehicles Symposium,Seoul, Korea, 2015, pp. 1148–1153.

[8] G. Notomista and M. Botsch, “Maneuver segmentation for au-tonomous parking based on ensemble learning,” in 2015 InternationalJoint Conference on Neural Networks (IJCNN), Killarney, Ireland,2015, pp. 1–8.

[9] H. Vorobieva, S. Glaser, N. Minoiu-Enache, and S. Mammar, “Auto-matic parallel parking in tiny spots: Path planning and control,” IEEETransactions on Intelligent Transportation Systems, vol. 16, no. 1, pp.396–410, 2015.

[10] K. Min and J. Choi, “A control system for autonomous vehiclevalet parking,” in 2013 13th International Conference on Control,Automation and Systems (ICCAS 2013), Gwangju, South Korea, oct2013, pp. 1714–1717.

[11] D. A. de Lima and A. C. Victorino, “Sensor-Based Control with DigitalMaps Association for Global Navigation: A Real Application forAutonomous Vehicles,” in 2015 IEEE 18th International Conferenceon Intelligent Transportation Systems, Las Palmas, Spain, 2015, pp.1791–1796.

[12] Y. Kang, D. A. de Lima, and A. C. Victorino, “Dynamic obsta-cles avoidance based on image-based dynamic window approachfor human-vehicle interaction,” in 2015 IEEE Intelligent VehiclesSymposium (IV), Seoul, South Korea, jun 2015, pp. 77–82.

[13] O. Kermorgant and F. Chaumette, “Dealing with constraints in sensor-based robot control,” IEEE Transactions on Robotics, vol. 30, no. 1,pp. 244–257, 2014.

[14] N. Andreff, B. Espiau, and R. Horaud, “Visual Servoing from Lines,”International Journal of Robotics Research, vol. 21, no. 8, pp. 679–699, 2002.

[15] V. K. Narayanan, F. Pasteau, M. Marchal, A. Krupa, and M. Ba-bel, “Vision-based adaptive assistance and haptic guidance for safewheelchair corridor following,” Computer Vision and Image Under-standing, vol. 149, pp. 171–185, 2016.

[16] O. Kanoun, F. Lamiraux, and P.-B. Wieber, “Kinematic control ofredundant manipulators: generalizing the task priority framework toinequality tasks,” IEEE Trans. on Robotics, vol. 27, no. 4, pp. 785–792, 2011.