• Nem Talált Eredményt

Path Tracking Algorithms for Non-Convex Waiter Motion Problem

N/A
N/A
Protected

Academic year: 2022

Ossza meg "Path Tracking Algorithms for Non-Convex Waiter Motion Problem"

Copied!
8
0
0

Teljes szövegt

(1)

Cite this article as: Nagy, Á., Csorvási, G., Vajk, I. " Path Tracking Algorithms for Non-Convex Waiter Motion Problem", Periodica Polytechnica Electrical Engineering and Computer Science, 62(1), pp. 16–23, 2018. https://doi.org/10.3311/PPeecs.11606

Path Tracking Algorithms for Non-Convex Waiter Motion Problem

Ákos Nagy1*, Gábor Csorvási1, István Vajk1

1 Department of Automation and Applied Informatics, Faculty of Electrical Engineering and Informatics, Budapest University of Technology and Economics, H-1521 Budapest, P.O.B. 91, Hungary

* Corresponding author, email: akos.nagy@aut.bme.hu

Received: 20 October 2017, Accepted: 09 December 2017, Published online: 07 February 2018

Abstract

Originally, motion planning was concerned with problems such as how to move an object from a start to a goal position without hit- ting anything. Later, it has extended with complications such as kinematics, dynamics, uncertainties, and also with some optimality purpose such as minimum-time, minimum-energy planning. The paper presents a time-optimal approach for robotic manipulators.

A special area of motion planning is the waiter motion problem, in which a tablet is moved from one place to another as fastas possible, avoiding the slip of the object that is placed upon it. The presented method uses the direct transcription approach for the waiter problem, which means a optimization problem is formed in order to obtain a time-optimal control for the robot. Problem formulation is extended with a non-convex jerk constraints to avoid unwanted oscillations during the motion. The possible local and global solver approaches for the presented formulation are discussed, and the waiter motion problem is validated by real-life experimental results with a 6-DoF robotic arm.

Keywords

motion planning, minimum-time control, time-optimal control, convex optimisation, robot control

1 Introduction

Time-optimal motion planning has been a topic of active research since the 1980. Minimum-time algorithms can maximize productivity, and reduce energy consumption of the robotic system. Direct approaches [1] or one step methods solve the entire problem in one step. In general it is a highly difficult task, since both the geometric con- straints (including collision avoidance), and the timing along this geometric path (including dynamic limitation) have to be optimized.

As an alternative to direct approach, the motion plan- ning problem is often decoupled [2, 3]. First, a high-level geometry path planner determines a path for the robot considering geometric constraints and ignoring sys- tem dynamics. In the next stage (path tracking), a veloc- ity profile for a predefined path is generated, where all constraints of the robot are applied for the fixed path.

Decoupled approach is preferred to direct approach for its lower computational time.

In this paper, we will focus on the second stage of the decoupled motion planning approach. Since the desired path of the robot is already defined, a scalar path coordinate

(θ(t)) can be used to represent robot position on the path [4-7]. The major advantage of the scalar path coordinate is that the high dimensional state-space model of the robotic system can be reduced.

Generally there are three different approaches to solve the decoupled minimum-time control problem. Indirect methods are based on the Pontryagin Maximum Principle:

the optimal bang-bang control is obtained by integrating maximum and minimum accelerations, and finding opti- mal switching points, where the active constraints can be changed [8-10]. Dynamic programming approach divides the state space into a discrete grid, and the optimal solu- tion is found in this plane [11, 12]. Direct transcription is the third velocity profile generation method. The opti- mal control problem can be cast as a convex optimiza- tion problem [5, 13]. Existing efficient convex optimisa- tion solvers can be used in these methods in order to get minimum-time solution, and the convexity guarantees a globally optimal solution. Using direct transcription, the objective function can be extended with other criteria, i.e.

thermal energy (integral of the square of the torque of

(2)

joints), torque jumps (integral of the absolute value of the rate of change of the torque) [5]. However convex refor- mulation fails to address many practical applications (e.g.

torque rate constraints, velocity-dependent torque con- straints, jerk constraints) since these applications intro- duce terms that destroy the convexity.

In this paper, a direct transcription formulation for the time-optimal waiter problem with joint jerk constraints is presented. In the so-called waiter motion problem a tablet in the gripper of the robot manipulator is moved from one pose to the other such that the object resting on the tablet does not slide at any time during the movement.

Due to the bang-bang nature of time-optimal control, near infinite jerks can be occurred in the resulted trajectory, and this usually results unwanted oscillations. These vibra- tions can be eliminated by jerk constraint. Since the joint jerk limitation cannot be written as a convex constraint, the convex reformulation is not possible in this case. However these constraints can be written as a difference of two con- vex (DC) functions, and using existing DC solver methods, optimal or near-optimal control can be obtained.

The paper is organized as follows. In Section 2 the time-optimal waiter motion problem is presented with non-convex jerk constraint. The formulation is based on the work of Verscheure et al. [5], Debrouwere et al. [14]. A possible solver methods for the presented problem are dis- cussed in Section 3. In Section 4, the generated velocity profile for a 6-DoF robotic manipulator is examined. Real- life experimental results are also presented in Section 4 with the 6-DoF robot.

2 Problem Formulation

In this section the non-convex time-optimal control prob- lem is introduced using non-linear change of variables.

In the presented approach, a mathematical optimisation problem is formed based on the work of Verscheure et al.

[5], Debrouwere et al. [14].

2.1 General Time-Optimal Formulation

During problem formulation q(t) ∈ p indicates a p-di- mensional generalized coordinate vector representing the configuration of the robot. The dynamic equation of a p-DoF robotic system is defined by using the second-order Lagrange equation [5]

τ( )t =M q t q t C q t q t q t d q t( ( )) ( ) + ( ( ), ( )) ( )  + ( ( )), (1) where τ(t) ∈ p is the generalized force vector, (∙) indi- cates time derivative, M

(

q t

( ) )

:p ++p is the mass

matrix, C

(

q t q t

( )

,

( ) )

:2p p p× is a matrix account- ing for centrifugal, Coriolis effects (it is linear in q), and d q t

( ( ) )

:p p accounts for joint position dependent forces (e.g. gravity).

Consider the predefined geometric path s(θ(t)) as a function of a scalar path coordinate (θ(t)) given in joint space coordinates. Using the chain rule, the kinematic equations (including jerk) for the robot can be derived (from now on, the time dependency is omitted)

q s q s

q s s

q s s

=

( )

= ′

( )

= ′

( )

+ ′′

( )

= ′

( )

+ ′′

θ θ θ

θ θ θ θ

θ θ θ

 

  

 

2

3

(( )

θθ+ ′′′s

( )

θ θ3

(2)

where s

( )

θ : , →[0 1]p, θ : ,[0T]→ ,[0 1], s

( )

θ =dsd( )θθ ,

′′

( )

= ( )

s θ d sd2θθ2 , s′′′

( )

θ =d sd3θ( )θ3 and T is the time when the robot reaches the end of the path. We also assume that θ ≥ 0 holds everywhere, which is a general assumption in time-optimal control.

The position vector of the end-effector (r(t) ∈ SE(3)) in the operational space is also considered. The conversion between the joint space and the operational space coordi- nates can be obtained by the following formula

q t

( )

r t

( )

,

ϕ ϕ1

(3)

where φ(q) and φ−1(q) are direct and inverse kinematics of the robot respectively.

The analogous equations for the operational space coor- dinates (without Cartesian jerk) can be written as

r p= ( )θ (4)

 

r p= ′

( )

θ θ (5)

r p= ′

( )

θ θ+ ′′p

( )

θ θ2, (6) where p(θ) is the fixed path of the end-effector.

A new variable is introduced for the problem formulation

b

( )

θ :=θ2 (7)

and using (7) the derivatives of the scalar path coordinate are defined by the derivatives of b(θ)





θ θ

θ θ

θ θ θ

=

( )

= ′

( )

= ′′

( ) ( )

b b

b b

1 2 1 2

(8)

From now on, b(θ), b'(θ) and b"(θ) are considered to be the variables of the optimization problem. To create a

(3)

finite dimensional problem we will discretise the problem in n + 1 points in the θ = [0…1] range. The i-th point is indicated by θi  . The discretisation is based on the assump- tion that b"(θ) is constant between two discretisation points, therefore b'(θ) is linear, and b(θ) is quadratic in θ

( )

= ′

( )

+ ′′

( ) (

)

( )

=

( )

+ ′

( ) (

b b b

b b b

i i i

i i i

θ θ θ θ θ

θ θ θ θ θ

1 1

1 1 1

))

+ ′′

( ) (

)

[ ]

=

(

+

)

= …

1 2

2 1

1 2

1 1

b

i n

i i

i i i i i

θ θ θ

θ θ θ, θ θ θ / , , ,

(9) where b"(θ) is evaluated at the midpoint of the interval since it is discontinuous in the discretisation points. The other variables are evaluated at θi

bi:=b

( )

θi bi′ = ′: b

( )

θi bi′′ = ′′: b

( )

θi (10)

The relationship between the variables in discrete time can be defined by

′′= ′ − ′

= +

(

′ + ′

)

= − = , ,

b b b d

b b b b d

d i

i i i

i

i i i i i

i i i

1

1 1

1

1 2

1 θ

θ

θ θ θ  nn.

(11)

The Lagrange dynamics of the robot is evaluated in every θi using (1), (2), (8)

τi =1m b c b d ii i′ + i i+ i = , n,

2 0, (12)

where the parameters of equation are written as

m s s

c s s s s s

d d s

i i i

i i i i

i i

: : :

=

( )

=

( )

′′+

(

, ′

)

=

( )

,

M

M C 1 1 (13)

and these parameters are also evaluated in θi

τi:=τ θ

( )

i si:=s

( )

θi si′ = ′: s

( )

θi si′′ = ′′: s

( )

θi (14) The derivatives of the path should be specified for (12).

When s(θ) is differentiable, si′ and si′′ can be calcu- lated analytically. Otherwise an approximation method is necessary for the derivatives (e.q.: numerical derivation, spline interpolation) [6, 14].

The acceleration and the jerk of the p-DoF robot are discretised similar to dynamics based on (2), (8)





q s b s b

q s b b s b b s b b

i i i i i

i i i i i i i i i

= ′ ′ + ′′

= ′ ′′ + ′′ ′ + ′′′

1 2 1 2

3

2 ,,

(15)

where qi is evaluated at the midpoints

 q q s s s s s s

b

i i i i i i i i

i

: : : :

:

=

( )

′ = ′

( )

′′ = ′′

( )

′′′ = ′′′

( )

θ θ θ θ

== ′ + ′ = + ′ + ′

 

 ,

b bi i 1 bi bi 1 bi bi1 d i 2

1 8

3

: 8 θ (16)

where bi can be derived using (9), (11)

b b b b d b d

b b b d b

i i i i i

i i

i i i

i

θ θ θ

θ

( )

= = + ′ + ′′

= + ′ + ′ − ′

1 1

2

1 1

2 1

2 4

2 bb d

b b b b d

i i

i i i i

( )

= + ′ + ′

 



1

1 1

8 1

8 3 8

θ

θ (17)

It should be note that using the presented discretisation approach, q

( )

θ , q

( )

θ , q

( )

θ are non-linear between two subsequent points.

The goal of the problem formulation is to generate time-optimal motion for the robot, therefore the objective function of the optimisation problem is the motion time (T ), which can be expressed by variable b(θ) :

T =

T dt=

( )T d =

b

( )

d ,

( )

0 0

1 0

1 1 2

1 θθ θ θ θ θ (18)

which is a convex function of b(θ) . Computing T in discrete time by numerical integration based on (9) would result a non-convex objective function. Therefore an another approximation is applied for T , in which b(θ) is linear in θ . This technique is also used in the work of Debrouwere et al. [14]. So the approximated T  is a convex function of bi

T d

b b

i

n i

i i

≈ +

 

.

=

2

1 1 2

1 1 2

θ (19)

2.2 Waiter Motion Constraint

Let us consider a waiter motion which consists of mov- ing a tablet carrying a glass along a predefined path as fast as possible so that the objects placed on it do not slide. The problem is introduced in the work of Flores and Kecskeméthy [9] using an indirect approach. The opti- mal trajectory is constructed by integrating the system equations forward and backward in time from switching points. The drawback of this approach is that it is difficult to accurately determining these switching points.

In this paper a different method is presented, where a con- vex sliding constraint is defined in the problem formulation.

Similar result to the presented work can be found in [15, 16].

Since the goal is that the object does not move on the tablet, a static friction model is used, and the no sliding condition can be written as

(4)

Fx2+Fy2 ≤µ0Fz (20)

F F F F

m r t g

x y z

=





=

(



( )

)

, (21)

where F is the force applied to the object excluding the gravity, Fx , Fy and Fz are the components of F in the local coordinate frame of the tablet, m is the object mass, g is the gravitational acceleration vector, μ0 is the dry friction coefficient between the contact surfaces and r indicates the translational part of object acceleration (first three coordinate of r). An illustration of the applied force (F) can be seen in Fig. 1.

In order to transform the sliding constraint to a convex form, rearrange (20) using Euclidean norm

F2 0 Fz

2 1

≤ µ + ⋅ . (22)

A friction angle (α) can be introduced to calculate μ0

µ0 =tanα, (23)

and Fz  can be also expressed using the normal vector of the tablet plane (n)

Fz = ⋅ .F n (24)

Substituting (25), (26) into (24), we get the convex form of the sliding constraint

F F n

2≤ ⋅

cosα (25)

Using (21), and simplify the formula with mass m , the obtained sliding constraint is

 

r g r g n

− ≤

(

)

2 cosα (26)

2.3 The Whole Optimization Problem

The complete optimization problem in discrete time is formed based on the presented constraints and objective function. Besides the sliding constraint, velocity, accel- eration, jerk and torque constraints are also considered in the model

min 2

1

1 1 2

1 1 2

1

1 i

n i

i i

i i

i

d b b b b b

d i n

=

+

 

 . . : ′′= ′ − ′

= , , θ

s t θ …

bb b b b d i n

b b b i n

b b

i i i i i

i i

i

= +

(

′ + ′

)

= , ,

′ = ′ + ′

= , ,

=

1 1

1

1

1

2 1

2 1

θ …

… :

ii i i i

i i i i i

b b d i n

r p b p b i

+ ′ + ′

 

 = , ,

= ′ ′ + ′′ = ,

1 1

1 8

3

8 1

1

2 0

θ …

……

,

= ′ ′ + ′′ = , ,

= ′ ′′

+ ′′ ′

n

q s b s b i n

q s b b s b

i i i i i

i i i i

i i

1

2 0

1 2 3

2 bb s b b

i n

m b c b d i n

b b i

i i i i

i i i i i i

i i

+ ′′′

= , ,

= ′ + + = , ,

≤ ≤ =

1

1

2 0

0 0

τ …

max ,, ,

− = , ,

n

q q q i n

qii qii qii i

max max

max max

 

 

0

== , ,

− = , ,

− ≤

(

)

1 0

2

n

i n

r g r g n

i i i

τ τ τ

α

max max

cos ,

 

(27) where bimax≥0 is a velocity limit, qimax0 is an acceler- ation limit, qimax0 is a jerk limit, τimaxd is a torque limit, and ’ , ’ represent componentwise inequalities.

Problem (29) is a finite dimensional non-convex prob- lem, where the optimisation variables are bi , bi′ and bi′′, all other parameters are defined before the optimisation, or can be expressed using the equality constraints.

Without the jerk constraint, the problem would be a convex optimization problem, as other constraints are affine or quadratic (sliding constraint), and the objective

Fig. 1 The presented scenario for the waiter motion problem. The F force applied to the object placed on the tablet.

(5)

function is convex. It would be namely a Second-Order Cone Programming (SOCP) problem, which could be solved efficiently using existing convex optimisation solvers.

3 Solver Methods for the Control Problem

In this section different solver methods for the presented problem are discussed. Due to non-convexity, local opti- mum points can be found in the feasible set of the problem.

Therefore local and global solvers are discussed separately in the followings.

3.1 Global Solvers

Before global solver methods are presented, the non-convex jerk constraint is reformulated

−  ′ ′′+ ′′ ′ + ′′′

 



qimaxb s bi i1 i s b s bi i i i qimax

2 3 1

2 (28)

Since square of root function is non-negative, (30) can be written as

s b s b s b q b s b

i i i i i i i

i i

1

2 3 1

2 0

1 2

1

′′+ ′′ ′ + ′′′ 2

 

 −

− ′ ′′

max

++ ′′ ′ + ′′′

 

 − 3 1

2 12 0

s b s bi i i i q bimax i

(29)

Since the left sides of (29) are affine, and the right side (bi12) is a convex function of bi, (29) can be formed as a difference of two convex function (DC function). DC functions have some appealing properties [17, 18], which makes it possible to find the global optimum faster than a general non-convex solver.

A general DC optimisation problem can be defined using DC constraints

min

, , ,

x

i i

f x

u x v x i l

( )

. . :

( )

( )

=

s t 0 0 (30)

where f(x), ui(x) and vi(x) are convex functions. Problem (27) can be considered as a general DC program (30), and existing solvers for DC programs can be applied for the presented waiter motion problem. In general, existing DC global solvers are not so efficiently as the convex solvers regarding to runtime, convergence and numerical stability.

A cutting plane procedure for DC program was devel- oped in [19]. To understand the cutting plane method, reformulate (30) to the following canonical form

min ( )

x f x

x D C

subject to ∈ int , (31)

where D and C are convex sets, and int C indicates the

interior of C . Every DC optimization problem can be writ- ten in canonical form [20].

If the DC program satisfy the so-called regularity con- dition [20], then the following optimality condition can be made: x* is global optimum of (31) if and only if

D x C

D x D x f x f x

( )

( )

= ∩

{

:

( )

( ) }

(32)

An example for (32) can be seen in Fig. 2. Cutting plane methods iteratively converges to a x* point from an initial, feasible point (x0). At every step, a convex polytope (Pk) is defined satisfying

D x

( )

k Pk

{

x f x:

( )

f x

( )

k

}

, (33)

If condition D x

( )

k C is true, then the actual xk is a global optimum. Otherwise a cutting plane is defined, and the polytope is refined using

Pk+1=Pk

{

x l x: k

( )

0

}

(34) A new xk + 1 should be also defined, and it can be proved that the presented method converges to a global optimum.

Branch and bound (B&B) based approach can be also used for (30) [17]. Due to the DC property of the constraints, lower and upper bounds of the objective function can be approximated. A B&B algorithm for non-convex time-op- timal problem is presented in [21], where a non-convex velocity-dependent torque constraint is applied, which is very similar to the presented jerk constraint (29).

Fig. 2 Example for the DC optimality condition. x* is a global optimum point, and D \ int C is the feasible set of the problem. The dashed line is

the contour line of the objective function.

(6)

3.2 Local Solvers

Local solvers for the general DC problem can perform sig- nificantly better compared to global methods. In this section a Sequential Convex Programming (SCP) algorithm [14] is presented as a local solver for the waiter motion problem.

The main idea behind the SCP algorithm is to itera- tively linearize the concave part of the DC constraints to transform the problem into a convex optimisation prob- lem. Guaranteed convergence to a local optimum can be proven for this method in contrast to general non-convex solution methods.

Suppose that xk is a given point, then the approximated problem is

min ( )

x

k

i i k

x i k k

f x x x

u x v x v x x x

i l

+ −

. . :

( )

( )

− ∇

( ) (

)

= , , ,

β 2

2

0 0

s t

 (35)

where DC constraints are linearised around xk , and β is a regularization factor added to the objective function to ensure proper convergence. The stopping criterion of the sequential algorithm can be the sufficiently low decrease of the objective function

Tk+1Tk ≤ , (36) where Tk indicates the travel time of the current iteration k.

4 Experimental Results

In this section the path tracking method is demonstrated in a real life scenario using a Mitsubishi RV-3SDB 6-DoF robot manipulator (see Fig. 3). A local solver (see Section 2) for the presented optimization problem isapplied to obtain a near time optimal trajectory for the waiter motion prob- lem. The solver is implemented in C++ using the state-of- art Gurobi commercial SOCP, LP solver [22].

4.1 Offline Velocity Profile Generation

A tablet was placed in the gripper of the robotic arm, and a empty glass was put on the tablet. The path of the gripper has been defined manually in operational space, and using inverse kinematics the joint space path was calculated (see Fig. 4). The orientation of the table was fixed during the motion, and it is defined using Euler angles. We used the Robotics Toolbox for Matlab [23] to calculate the inverse kinematics for the path. Based on the algorithm presented in Section 3.2 time parameterized trajectory was gener- ated for the waiter motion problem.

Velocity, acceleration, jerk, and a constraint accounting for sliding effect are used for the demonstration. Torque constraints were not used, because the dynamic parame- ters of the robot were not known at the time.

For sliding constraint of the problem formulation it was necessary to determine the friction angle (α) used in (25). We measured α by placing the glass on the table, and increased the angle of the tablet until the glass begun to slide. The actual value of α was 9° in our scenario.

Two generated velocity, acceleration and jerk profiles for the third joint of the robot can be seen in Fig. 5. Only the jerk constraint was different in the two profiles: sym- metrical 100 rad/s3 limit was used for the first case, and 5 rad/s3 for the second profile.

4.2 Real-Time Path Tracking

The real-time path tracking method has been implemented in the following way: the desired joint positions were sent

Fig. 3 Mitsubishi RV-3SDB robot.

Fig. 4 The fixed path (orange line) of the gripper in Matlab using the Robotics Toolbox.

-0.2 0 0.2

1 0.4 0.6

Z

0.8 1

0.5

Y 0

Y

-0.5 1

0.5

X 0 Z

-1 -0.5

X

-1

(7)

to the robot controller at the fixed cycle time of the con- troller (7.1 ms [24]) over a TCP/IP network connection.

The controller send back the joint positions, so the actual positions were also measured during path tracking.

The desired joint space path was equal to the predefined path, but it also had a time parameter. The actual posi- tion of the path was selected based on this time coordi- nate. To make the motion smoother, interpolation was used between path points.

As we used the predefined path as the control sig- nal, difference between the predefined and the traversed path was only depends on the accuracy of the robotic arm, which is negligibly small (max. ±0.02 mm in opera- tional space [25]). However, the velocity profiles can have

higher error due to the approximations of the path deriv- atives. The actual error in the velocity profile can be seen in Fig. 6 for the last joint.

5 Conclusion

In this paper, the well-known time-optimal control prob- lem has been discussed using the direct transcription approach. The problem formulation was extended with two, special property. A waiter motion task was consid- ered, which implied a convex sliding constraint in the problem formulation, and a non-convex jerk constraint was also taken into account. The possible global and local solver algorithms were discussed for the optimization problem. In the last section of the paper, experimental result has been presented using a 6-DoF robot manipu- lator based on a local method to the non-convex problem.

0.5 1 1.5 2 2.5 3 3.5

Time [s]

-1.1 -1 -0.9 -0.8 -0.7 -0.6 -0.5 -0.4

Velocity [rad/s]

Fig. 6 The difference between the reference and the measured velocities for the first joint. Dotted line is the reference velocity, the solid line is

the measured profile from the robot controller.

Fig. 5 The generated profiles for the third joint. For the solid profile higher jerk constraint (100 rad/s3) is used compared to the dotted one

(5 rad/s3).

References

[1] Choset, H., Lynch, K. M., Hutchinson, S., Kantor, G. A., Burgard, W., Kavraki, L. E., Thrun, S. "Principles of Robot Motion: Theory, Algorithms, and Implementations", MIT Press, Cambridge, MA, USA, 2005.

[2] LaValle, S. M. "Planning Algorithms", Cambridge University Press, New York, NY, USA, 2006.

[3] Ardeshiri, T., Norrlöf, M., Löfberg, J., Hansson, A. "Convex Optimization approach for Time-Optimal Path Tracking of Robots with Speed Dependent Constraints", In: Proceedings of 18th IFAC World Congress, pp. 14648–14653, Milano, Italy, 2011.

[4] Shin, K., Mckay, N. D. "Minimum-time control of robotic manip- ulators with geometric path constraints", IEEE Transactions on Automatic Control, 30(6), pp. 531–541, 1985.

https://doi.org/ 10.1109/TAC.1985.1104009

[5] Verscheure, D., Demeulenaere, B., Swevers, J., Schutter, J. D., Diehl, M. "Time-Optimal Path Tracking for Robots: A Convex Optimization Approach", IEEE Transactions on Automatic Control,54(10), pp. 2318–2327, 2009.

https://doi.org/10.1109/TAC.2009.2028959

[6] Lipp, T., Boyd, S. "Minimum-time speed optimisation over a fixed path", International Journal of Control, 87(6), pp. 1297–1311, 2014.

https://doi.org/10.1080/00207179.2013.875224

[7] Hauser, K. "Fast Interpolation and Time-Optimization on Implicit Contact Submanifolds", In: Proceedings of Robotics: Science and Systems, Berlin, Germany, 2013.

[8] Bobrow, J. E., Dubowsky, S., Gibson, J. S. "Time-optimal Control of Robotic Manipulators along Specified Paths", International Journal of Robotics Research, 4(3), pp. 3–17, 1985.

https://doi.org/10.1177/027836498500400301

0 0.2 0.4 0.6 0.8 1

-1 0 1

Velocity [rad/s]

0 0.2 0.4 0.6 0.8 1

-5 0 5

Acceleration [rad/s2]

0 0.2 0.4 0.6 0.8 1

-100 0 100

Jerk [rad/s3]

(8)

[9] Flores, F. G., Kecskeméthy, A. "Time-Optimal Path Planning Along Specified Trajectories", In: Gattringer, H., Gerstmayr, J. (eds.), Multibody System Dynamics, Robotics and Control, (pp. 1–16.), Springer, Vienna, 2013.

https://doi.org/10.1007/978-3-7091-1289-2_1

[10] Consolini, L., Locatelli, M., Minari, A., Piazzi, A. "An optimal com- plexity algorithm for minimumtime velocity planning", Systems &

Control Letters, 103, pp. 50–57, 2017.

https://doi.org/10.1016/j.sysconle.2017.02.001

[11] Oberherber, M., Gattringer, H., Müller, A. "Successive dynamic pro- gramming and subsequent spline optimization for smooth time op- timal robot path tracking", Mechanical Sciences, 6(2), pp. 245–254, 2015.

https://doi.org/10.5194/ms-6-245-2015

[12] Max, G., Lantos, B. "Time optimal control of four-in-wheel-motors driven electric cars", Periodica Polytechnica Electrical Engineering and Computer Science, 58(4), pp. 149–159, 2014.

https://doi.org/10.3311/PPee.7806

[13] Nagy, Á., Vajk, I. "LP-based Velocity Profile Generation for Robotic Manipulators", International Journal of Control, 2017.

https://doi.org/10.1080/00207179.2017.1286535

[14] Debrouwere, F., Loock, W. V., Pipeleers, G., Tran, D. Q., Diehl, M., Schutter, J. D., Swevers, J. "Time-Optimal Path Following for Robots With Convex-Concave Constraints Using Sequential Convex Programming", IEEE Transactions on Robotics, 29(6), pp.

1485–1495, 2013.

https://doi.org/10.1109/TRO.2013.2277565

[15] Duijkeren, N. V., Debrouwere, F., Pipeleers, G., Swevers, J.

"Cartesian constrained time-optimal point-to-point motion planning for robots : the waiter problem", In: Benelux Meeting on Systems and Control, Lommel, Belgium, 2015.

[16] Csorvási, G., Nagy, Á., Vajk, I. "Near Time-Optimal Path Tracking Method for Waiter Motion Problem", In: Proceedings of 20th IFAC World Congress, pp. 5080–5085, Toulouse, France, 2017.

[17] Tuy, H. "Convex Analysis and Global Optimization", 2nd ed., Springer International Publishing, 2016.

https://doi.org/ 10.1007/978-3-319-31484-6

[18] Zhang, Q. "A new necessary and sufficient global optimality condi- tion for canonical DC problems”, Journal of Global Optimization, 55(3), pp. 559–577, 2013.

https://doi.org/10.1007/s10898-012-9908-1

[19] Tuy, H. "Canonical DC programming problem: Outer approxima- tion methods revisited", Operations Research Letters, 18(2), pp.

99–106, 1995.

https://doi.org/10.1016/0167-6377(95)00037-X

[20] Horst, R. "Handbook of Global Optimization", Springer US, 1995.

https://doi.org/10.1007/978-1-4615-2025-2

[21] Nagy, Á., Vajk, I. "Minimum-Time Path Tracking for Robots with Non-Convex Constraints", In: Proceedings of the 15th International Symposium on Intelligent Systems and Informatics (SISY), pp.

163–168, 2017.

[22] Gurobi Optimization, Inc., Gurobi Optimizer Version 7.0.2.

[Computer software], 2017.

[23] Corke, P. I. "Robotics, Vision and Control: Fundamental Algorithms in Matlab", Springer, 2011.

[24] Mitsubishi, CR750/CR751 Series Controller Instruction Manual, 2014.

[25] Mitsubishi, RV-3SD/3SDJ/3SDB/3SDBJ Series: Standard Specifications Manual, 2009.

Hivatkozások

KAPCSOLÓDÓ DOKUMENTUMOK

We prove that two strictly convex bodies in the plane subtending the same angles at each of the points of two parallel straight lines and a big closed curve, must

The goal of this paper is to reformulate the design of vehicle path tracking functionality as a modeling problem with learning features and a control design problem using a model-

Therefore, the coordinated design is formed as an optimal control problem, which is solved through two optimization tasks.. A quadratic optimization task with online solution is

The tracking control problem of the autonomous vehicle is formed in a Model Predictive Con- trol (MPC) structure, in which the result of the big data analysis is incorporated..

In Section 2 the time optimal control problem of the single-track vehicle is for- mulated and it is solved in Section 3 by the multiple shoot- ing method using time, state and

For the latter purpose the optimal solution of the ILP algorithm was used as reference in those problem instances that both algorithms were able to solve in acceptable time.. We

The proposed paper applies a new optimization method for optimal gain tuning of controller parameters by means of ABC algorithm in order to obtain high performance of the

From a numerical point of view the disadvantage of the first method is to double the order of the matrix, while in the second procedure already the coefficients of