• Aucun résultat trouvé

Homotopic particle motion planning for humanoid robotics

N/A
N/A
Protected

Academic year: 2021

Partager "Homotopic particle motion planning for humanoid robotics"

Copied!
7
0
0

Texte intégral

(1)

HAL Id: hal-01137918

https://hal.archives-ouvertes.fr/hal-01137918

Preprint submitted on 31 Mar 2015

HAL is a multi-disciplinary open access

archive for the deposit and dissemination of

sci-entific research documents, whether they are

pub-lished or not. The documents may come from

teaching and research institutions in France or

abroad, or from public or private research centers.

L’archive ouverte pluridisciplinaire HAL, est

destinée au dépôt et à la diffusion de documents

scientifiques de niveau recherche, publiés ou non,

émanant des établissements d’enseignement et de

recherche français ou étrangers, des laboratoires

publics ou privés.

Homotopic particle motion planning for humanoid

robotics

Andreas Orthey, Vladimir Ivan, Maximilien Naveau, Yiming Yang, Olivier

Stasse, Sethu Vijayakumar

To cite this version:

Andreas Orthey, Vladimir Ivan, Maximilien Naveau, Yiming Yang, Olivier Stasse, et al.. Homotopic

particle motion planning for humanoid robotics. 2015. �hal-01137918�

(2)

Homotopic particle motion planning for humanoid

robotics

Andreas Orthey

1

, Vladimir Ivan

2

, Maximilien Naveau

1

, Yiming Yang

2

, Olivier Stasse

1

, Sethu Vijayakumar

2

Abstract—Exploiting structure is essential to an understanding of motion planning. Here, we exploit the topology of the envi-ronment to discover connected components. Inside a connected component, instead of planning one trajectory in configuration space, motion planning can be seen as optimizing a set of homotopically equivalent particle trajectories. In this paper, we will concentrate on the problem of motion planning for a humanoid robot. Our contributions are: i) finding the homotopy classes of a single footstep trajectory in an environment, ii) finding a single footstep trajectory in a single homotopy class formulated as a convex optimization problem, and iii) finding a feasible upper body trajectory given a footstep trajectory, formulated as a set of convex optimization problems. This view provides us with important insights into the difficulty of motion planning, and – under some assumptions – allows us to provide the number of local minima of a given motion planning problem. We demonstrate our approach on a real humanoid platform with 36-dof in a highly restricted environment.

I. INTRODUCTION

Motion is one of the fundamental building blocks of in-telligent behavior, and a deep understanding would enable robots to achieve autonomous tasks in eldery care, deep space exploration, and nuclear waste removal.

We study here the motion planning problem A = {R, C, qI, qG, E} [1] with R be a robotic system, C the

configuration space of R, qI ∈ C the initial configuration,

qG∈ C the goal configuration and E the environment.

The motion planning problem was shown to be NP-hard [2], and for humanoid robots, computational time can become several hours in a narrow environment [3], [4], [5]. We argue that the main problem is the reliance on random sampling techniques [6]: if the subset of feasible configuration gets arbitrarily small, the convergence rate of random sampling gets arbitrarily high [7]. While random sampling is excellent for solving the problem in general, we argue here that to design truly efficient algorithms, we need to study, understand and exploit the underlying structure of the motion planning problem.

Here, we concentrate on investigating and exploiting the environment structure by extracting homotopy classes. A ho-motopy class is a set of functions, which can be continuously

This research has received funding from the European Union Seventh

Framework Programme (FP7/2007 - 2013) under grant agreement no611909,

KoroiBot.

1 are with the CNRS, LAAS,7 av. du Colonel Roche, F-31400, Toulouse,

France, Univ de Toulouse, LAAS, F-31400, Toulouse, France {aorthey,mnaveau,ostasse} at laas.fr

2 are with the University of Edinburgh, Edinburgh, UK

{vivan,yiming.yang,sethu.vijayakumar} at ed.ac.uk f3 f2 f1 xI xG

Fig. 1. Left: Two functions are in the same homotopy class, if they can be continuously deformed into each other, while fixing their end points. f1

would be not homotopically equivalent to f2, while f3 would be. Right: In

3d, we conduct homotopic motion planning for a set of particles, particles with homotopically equivalent space curves.

deformed into each other, as depicted in Fig. 1. For each homotopy class, we consider the trajectories of a set of particles {τk}ηk=0 on the robot body moving through R

3 on

space curves of the form τk : [0, 1] → R3. We assume here that

all particle trajectories are homotopically equivalent. Motion planning can then be conducted in the environment by first finding a single particle trajectory, and then finding all particles on the robot body by restricting them to belong to the same homotopy class as the single particle trajectory.

Towards this goal, we decompose the open space of the environment into smaller volumes and analyze their cover-ing to compute homotopy classes of robot particles movcover-ing through open space. We argue here that performing motion planning locally in one homotopy class ensures continuity, which is a requirement for optimization based planners. This decomposition of motion planning is called homotopic motion planning [8].

Our contributions are

• Identification of the homotopy classes in a given

environ-ment for a sliding footstep and the approximation of the free space

• Formulation of the problem of finding a sliding contact trajectory in one homotopy class as a convex optimization problem

• Formulation of the problem of finding a set of particle trajectories on the robot body, which are constrainted by the contact trajectory, as a set of convex optimization problems

Sec. II describes how we we decompose an environment into walkable surfaces, homotopy classes and the free space inside of one homotopy class. Sec. III formulates optimizing

(3)

Sec. II E S B I xI, xG H GE Sec. III H τ0 xI, xG Sec. IV τ0 P Υ I X C

Fig. 2. The conceptual overview about this paper. Top: in section II we decompose the environment E into walkable surfaces S, intersections I and intersections I. From the start contact xI, the goal contact xG and the

connectivity graph GEwe compute the homotopy classes H on S. Middle:

Given the homotopy classes H, the start contact xIand the goal contact xG,

we compute a sliding footstep trajectory τ0, supported on H. Bottom: We

compute upper-body particle trajectories Υ from a given footstep trajectory τ0, planes P , cuboids B, and from cross-sections X generated by sampling

robot configurations C.

a single footstep trajectory as a convex optimization problem, and Section IV formulates the upper body optimization as a set of convex optimization problems under convex inequality constraints from the environment. The reader is refered to consult Fig. 2 for a technical overview.

II. ENVIRONMENTHOMOTOPYDECOMPOSITION

In this section, we describe how we compute the free space of a given environment, and its connectivity. We start by reasoning about surfaces on which a foot contact is possible, which we call walkable surfaces. For each walkable surface, we compute its free space stack, a set of boxes on top of the surface in which the swept volume of the robot R necessarily has to lie. We further represent the connectivity of surfaces by a graph structure. This graph structure then enables us identify homotopy classes.

We will consider a decomposition of the environment into a set of objects as

E = O1t · · · t Oα (1)

with Oi being a bounded convex polytope

Oi = {x ∈ R3|a (i)T j x ≤ b (i) j , ka (i) j k2= 1, j ∈ [1, αi]} (2)

We make here the assumption that every object Oi is a

convex polytope. If an object is not a convex polytope, we decompose it into convex subobjects [9], such that we can operate w.l.o.g. on convex polytopes.

For every object Oi, we define the p-th surface element as

Sip= {x ∈ R3|a(i)Tp x = b (i) p , a (i)T j x ≤ b (i) j , j = 1, · · · , p − 1, p + 1, · · · , αi} (3)

with a(i)p the surface normal, and b(i)p the distance to the origin.

Definition 1 (Walkable Surface). A surface element Spi is

called walkable, if

1) the slope of Sip is smaller than the maximum slopeRθ

the robot can stand on ka(i)

p − vgk ≤

p

(2 − 2 cos(Rθ)) (4)

withvg= (0, 0, 1)T

2) the foot of radius RFR is fully contained inside S p i,

meaning the following convex problem is feasible (based on the maximum inscribed circle problem [10])

maximize x∈Rn,r∈R R subject to aTi x + RaTia0i≤ bi, i = {1, · · · , p − 1, p + 1, · · · , αi} aTpx = bp R ≥ RFR (5)

wherebyr is the radius of the circle, x the center, a0i is the orthogonal projection onto the hyperplane ofap, i.e.

a0i= ai− (aTiap)ap. Visualized in Fig. 3. R x B p i(0, δ) Bip(δ, 2δ) Bp i(2δ, 3δ) Sp i

Fig. 3. Left: a polytope (light gray), a surface element (dark gray) and an inscribed circle with radius R and center x. Right: a set of cuboids Bipon top of one surface element Sip(dark gray)

We now add a notion of connectivity:

Definition 2 (Connectivity). Two walkable surfaces Si, Sjare

called connected, iff d(Si, Sj) < RStep, with RStep being the

maximum step size of the robot R

This connectivity gives rise to a graph structure GE, which

contains walkable surfaces a nodes, and an edge between two connected surfaces.

To approximate the free space, we stack cuboids on top of each walkable surface. A cuboid of height δ and with distance ∆L to Sipis defined as B

p

i(∆L, ∆L+ δ) See Fig. 3. The stack

of cuboids on Sip will be denoted by Bip= {Bi,kp }βk=1

Bpi,k= Bip(kδ, (k + 1)δ)} (6) β is choosen such that β > RHU

δ with RHU the maximum

height of the robot. For each Bi,kp , we apply a clipping algorithm [11] to decompose it into smaller convex cuboids.

Additionally we define the intersection element between two stacks of cuboids Bi, Bj as Iij = Bi∩ Bj.

(4)

S0 S1 · · · SR−1 SR

τ (t0, t1) τ (t1, t2) · · · τ (tR−1, tR) τ (tR, tR+1)

Fig. 4. A function τ has support on a walkable surface Si at the time

[ti, ti+1].

Now, given two configurations qI, qG ∈ C of the robot, we

compute the right foot position as xI = T (qI), xG = T (qG)

by using a forward kinematics operator T . Given xI, xG, we

define SI = argmin Sk∈S

d(xI, Sk) to be the initial surface, and

SG= argmin Sk∈S

d(xG, Sk) to be the goal surface.

Given SI, SG, we compute H = {H1, · · · , HR}, the set of

R simple connected paths on the environment graph GE. We

call H ∈ H a homotopy, and we will write the connection of walkable surfaces as H : S0 → · · · → SRH. As a note, the

complexity of finding all connected paths in a graph with V vertices is O(|V |!) [12].

To summarize, in this section we preprocessed the environ-ment E, to decompose it into

• A set of Nw walkable surfaces S1, · · · , SNw

• A set of Nw stack of cuboids B1, · · · , BNw

• A set of Ni connector elements I1, · · · , INi

• The environment graph GE, describing the connectivity

between walkable surfaces

• A set of homotopies H for given xI, xG

III. CONVEX OPTIMIZATION OFFOOTPATHHOMOTOPIES

Given H : S0→ · · · → SRH, our goal is to find a sliding

footstep trajectory supported on the surfaces S0, · · · , SRH.

More formally, we will consider the functional space of space curves as

Ω(xI, xG, H) = C1([0, 1], R3) (7)

under the constraints that for all τ ∈ Ω(xI, xG, H) we have

τ (0) = xI, τ (1) = xG, and that a segment τ (t) for t ∈

[ti, ti+1] has support on a walkable surface Si, as depicted in

Fig. 4. In between support, we assume that the function is not supported, i.e. the foot can freely move through space, under the restriction that the non-support movement is smaller than the maximum stepsize.

We represent the functional space Ω(xI, xG, H) by a linear

combination of basis functions [10], based on the Stone-Weierstrass theorem. The Stone-Stone-Weierstrass theorem [13] guarantees that every continuous function from C([0, 1], R3)

can be approximated arbitrarily close by a polynomial func-tion, i.e. we have

Theorem 1 (Stone-Weierstrass). Let τ ∈ C1

([0, 1], R3). For

every  > 0 there exists a polynomial p(t) =

P

i=0

witi such

GE

Fig. 5. Two homotopy classes of footsteps, and two solutions, obtained by solving one convex optimization program in each homotopy class. Also we show the environment graph GEfor this particular example, which represents

connectivity between walkable surfaces.

Fig. 6. Four homotopy classes in the environment: Our algorithm finds the homotopy classes via graph search, and then solves one convex optimization problem in each class to find the global optimal solution trajectory.

that for allt ∈ [0, 1] we have kτ (t) −

X

i=0

witik <  (8)

Conceptually, we represent a continuous function by a linear combination of an infinite set of basis functions. We will make the assumption that higher-order terms are negligible such that we choose a finite K  0, and use p(t) =

K−1 P i=0 witi. We will denote F = {x0, · · · , xK−1 } ∈ RK×D, with K

basis functions, and D the discretization of [0, 1]. For all t ∈ [0, 1] we denote the approximation by τ = WTF (t),

with W ∈ RK×3. The complete convex optimization problem

in homotopy class H becomes

minimize τ ∈Ω(xI,xG,H) c(τ ) (9) subject to τ (0) = xI, τ (1) = xG (10) ∀Si∈ {S0, · · · , SR}, t ∈ [ti, ti+1] : Aiτ (t) ≤ bi (11) ∀t ∈ [0, 1] : kτ (t) − τ (t + ∆t)k ≤ RStep (12) ∀t ∈ [0, 1] : kτ (t) − WTF (t)k ≤  (13) whereby we have the following parameters

(5)

TABLE I

RESULTS FOR PLANNING PATHS IN THE TWO SCENARIOS SHOWN INFIG. 5

ANDFIG. 6. RIS THE NUMBER OF HOMOTOPIES, TW IS THE TIME TO

EXTRACT WALKABLE SURFACES FROM THE ENVIRONMENT, TGTHE TIME

TO COMPUTE THE CONNECTIVITY BETWEEN SURFACES, TPTHE

PLANNING TIME OF SOLVINGRCONVEX OPTIMIZATION PROBLEMS,AND

TIS THE ACCUMULATED TIME OF ALL STAGES TOGETHER(AVERAGED

OVER10RUNS,ROUNDED).

Environment R Homotopies TW(s) TG(s) TP(s) T (s)

Stepping 1 (Fig. 5) 2 0.27 1.92 6.53 8.73 Stepping 2 (Fig. 6) 4 0.26 1.68 20.34 22.28

• RStep the maximum step size of the robot

•  > 0 approximation constant to circumvent numerical

instabilities

• K number of basis functions

• c(τ ) is a convex objective function on τ , for example the shortest path as c(τ ) = 1 R t=0 kτ (t) − τ (t + ∆t)k2 2dt

The given convex problem describes the set of all trajecto-ries restricted to one homotopy class. A valid footstep at t can be modeled as a convex inequality constraint:

∀t ∈ [0, 1] : Aiτ (t) ≤ bi− RFdiag(ATiA0i) (14)

whereby Ai = {a0, · · · , aMi} contains the normals of

the polytope associated to the walkable surface Si, A0i =

{a0

0, · · · , a0Mi} with a

0

j = aj− (aTjap)ap, and RF being the

radius of the foot. Compare to (5).

Fig. 5 shows the result of our convex optimization problem for an environment with 2 homotopy classes. A more complex version with 4 homotopy classes is shown in Fig. 6. The final planning results are depicted in Table I, all generated by using the splitting conic solver (SCS) [14] inside cvxpy [15].

IV. UPPERBODYOPTIMIZATION

We have showed so far how to optimize a single footstep trajectory τ0 ∈ Ω(xI, xG, H) in one homotopy class of the

environment via a convex optimization problem. Now we assume that τ0 is fixed. Our goal is to find a set of particle

trajectories in the same homotopy class as τ0, belonging to

the swept volume of R, such that those particles are feasible in E. To put if differently, instead of searching for a single configuration space trajectory, we are searching for a set of mutually constrained particle trajectories in the environment. This section describes one possible way to constrain those particle trajectories to lie in the same homotopy class as τ0.

Please consult also Fig. 2 for an overview.

Each particle of the swept volume moves along a space curve in R3. Let Υ = {{τl

k, τkr}} η

k=0be the set of space curves

of 2(η + 1) particles, with τk{l,r} ∈ C1

([0, 1], R3), and τl k

represents the left outer hull of the swept volume of the robot at height kδ, and τr

k the right hull. If we take a cross-section of

the swept volume, then τk is represented by a point at height

kδ, as depicted by the red dots in Fig. 7. To achieve this, we apply three constraints on the functional space Υ

1) τk(t) ∈ P (t), the plane orthogonal to the foot trajectory

τ0 at instance t (cmp. Fig. 8) P (t) = {x ∈ R3|aT P(t)x = bP(t)} (15) with aP(t) = τ00(t) kτ0(t)k and bP(t) = a T(t)τ 0(t).

2) τk(t) has to be feasible in E, i.e. if τ0 is supported on

Sip at t, then

τk(t) ∈ Bip(kδ, (k + 1)δ) (16)

3) At instance t, all particles resemble a cross-section Xk

of the robot

τk ∈ Xk (17)

The first two constraints are a linear equality and a convex inequality, respectively. The third constraint however is non-convex. To obtain Xk, we sample the configuration space C

and compute cross-sections. A cross-section of a configuration is defined as its swept volume on the plane in movement direction, i.e. at t, the volume of q ∈ C is projected onto P (t), as depicted in Fig. 7. As a simplification, we use only irreducible configurations of the robot [3]. An irreducible configuration is a configuration which has a minimal swept volume. Basically, we sample {q1, · · · , qσ} ∈ C, apply a

section operator φ : C → X × X and compute the cross-sections X = {{xl,1, xr,1}, · · · , {xl,N, xr,N}}. xl stands for

the left points of the swept volume, and xrfor the right points

and we note that xr= Alxl.

We now have to find a feasible cross-section for each plane. As a simplification, we consider the cross-sections only at intersections Ir of the environment, since those intersections

represent the narrow passages. We note that we have only convex boxes in-between intersections, and so we assume that we can linearly interpolate two intersection points.

Our algorithm proceeds in the following manner: we com-pute the feasibility of N cross-sections by solving N con-vex optimization problems Θi

1, · · · , ΘiN for all intersections

i ∈ [1, V ] in I1, · · · , IV. A feasible path is then a sequence

λ1, · · · , λV of feasible cross-sections Θ1λ1, · · · , Θ

V λV with

Θi

λj < ∞. We can represent this as a solution matrix

Λ =    Θ1 1 · · · ΘV1 .. . . .. ... Θ1 N · · · ΘVN    (18) whereby we have that Θi

j solves the problem of feasibility

of a cross-section Xj on an intersection element Ii. Let ti be

such that τ (ti) ∈ Ii. Then Θij becomes

Θij = minimize {τ0,··· ,τη}∈Υ c(τ0, · · · , τη) (19) subject to ∀k ∈ [0, η] : τk(ti), ALτk(ti) ∈ P (tr) (20) τk(ti), ALτk(ti) ∈ Ii(kδ, (k + 1)δ) (21) τk(ti), ALτk(ti) = Xj (22)

(6)

Fig. 7. Left: The cross-section space for a humanoid robot. Each line represents a certain height above a walkable surface. The cross-section of the robot intersects each height at two points, which we call xL and xR

for left and right, respectively. We assume that every cross-section gives rise to only two points, i.e. we ignore configurations, where this is not the case. Overlaid (white line segments) are the constraints by the wall environment, which impose a convex box inequality on the cross-sections.Right: the final experiment, with the humanoid robot HRP-2 walking through a narrow environment.

Fig. 8 represents the complete algorithmic output: from an environment, we compute walkable surfaces, we compute a footstep trajectory, we compute planes orthogonal to the footstep, we solve a set of convex optimization problems at each intersection, and we compute a final set of particle trajectories in the environment.

Finally, our main point here is that we have investigated the structure of the planning problem. Given our assumptions, we can compute the number of local minima of our planning problem as L = R X i=1 NVi (23)

with R the number of homotopy classes, N the number of cross-sections, and Vi the number of intersections inside the

i-th homotopy class. For the wall environment in Fig. 8 we have N = 144,V = 2,R = 1 and so L = 20736.

While our work is preliminary and non-complete, we want to stress the fact that knowing the number of local minima is important for understanding the inherent complexity of motion planning.

V. EXPERIMENTS

We implemented the algorithms in python, and used cvxpy [15] to compute solutions to the local minima. The source code to reproduced the experiments is available at

https://github.com/orthez/mpp-path-planner

For experimental verification, we have chosen the wall environment depicted in Fig. 8, which contains 145 objects.

The following parameters were used: β = 40, δ = 0.05, such that βδ = 2.0 > RH with RH = 1.539m the maximum

height of HRP-2 [16]. For Problem (9), we used  = 0.02, D = 1000, K = 2000, and we used a minimum number of Di= 15 samples for each walkable surface Si.

The environment decomposition took 3m20s, and our al-gorithm computed N = 144 cross-section configurations. We employ a greedy version of our algorithm, which computes

Fig. 8. From Left to Right, Top to Bottom: 1) all polytopes in the wall environment 2) the extracted walkable surfaces from our algorithm, 3) the footstep trajectory in the single homotopy class, computed by solving the convex optimization problem (9), 4) the vertical planes along the footstep trajectory, 5) the intersection of boxes on each walkable surface to create the connection elements 6) the final plan of workspace trajectories, all homotopically equivalent and representing a configuration space trajectory.

Planning Instance RRT [3] PP 0 3h37m 15m41s 1 6h07m 16m03s 2 3h55m 16m01s 3 9h34m 16m12s 4 6h37m 15m41s 5 0h44m 15m41s 6 16h19m 15m42s 7 2h45m 15m43s 8 43h57m 15m45s 9 2h03m 15m16s

Fig. 9. Comparison of running time on 10 instances for RRT (red) (adapted from [3]) and for our particle planning (PP) algorithm (blue). For PP, the time depends on the discretization

all local minima for the first intersection, and then checks if the next intersection can be solved by the solution to the first intersection. For each intersection, we computed all minima and found out that 11/144 have been feasible (7.64%). The computation took 12m15s (averaged over 10 runs). All together we have a total computation time of 15m35s. We compared the results of all runs with the results of a rapidly exploring random tree [6], operating on the irreducible con-figuration space [3]. The results in Fig. 9 show that we have a lower variance while performing better at the given sampling resolution.

To move the robot in the real world, we add small footsteps along the path, one every 0.1m. Given footsteps and trajectory of the upper body, we use a dynamical solver to compute zero-moment point trajectories for the robot. We have used those results to verify the motion in the dynamical simulator OpenHRP [17], and executed it on the humanoid robot HRP-2 [16]. The video can be found here

(7)

VI. RELATEDWORK

Bhattacharya et al. [8] compute homotopy classes in the environment, and use them as a constraint for graph-based search. Our work is complementary in the sense that we in-vestigate how to formulate planning in one homotopy class as a set of convex optimal problems, while their work investigates how to compute the homotopy classes in the first place.

The technique presented in [18] estimates a single homotopy class by growing random spheres. Our approach tries to be more systematic in that we reason about contact surfaces, and restrict the free space by the robots geometry. Also, we consider planning inside a homotopy class not as a potential field controller, but as a global optimization procedure.

The work by [19] consider sweeping a spherical object to find weakly collision free footstep positions. Our work is similar for footsteps but precomputes homotopy classes to identify high-level minima.

[20] identifies narrow passage in the environment, and com-putes important waypoint configurations inside those narrow passages. This idea inspired our computation of connector elements, elements which connect two contact surfaces.

Ivan et al. [21] introduce different topological representa-tions to easier solve certain subproblems of motion planning. Our work is complementary, in that we would be able to analyze which representation to use given a certain problem.

The authors of [22] discover convex regions of footsteps in an environment, and employ mixed-integer programming to find a solution. Our work explores how adding more structure in form of connectivity can help to discover the homotopy classes, and formulate the resulting problem as a set of convex optimization problems.

Farber [23] introduced the topological complexity of a con-figuration space. Our work can be seen as a practical means of identifying the covering of the workspace volume and thereby its topological complexity. Our optimization algorithms are then one proposal to find paths inside of a given covering.

This work is fundamentally based on the work by [3], who introduced irreducible configuration for humanoid robots. Our work is complementary in that we are restricting our motions to the space of irreducible configuration while exploiting environment structure.

VII. CONCLUSION

We decomposed the general motion planning problem into a set of homotopic motion planning problems, with the goal of developing more efficient algorithms for the homotopic motion planning problem.

We presented three results: I) how to identify homotopy classes in an environment, based on walkable surfaces, sur-faces on which a robot can make a foot contact. II) how to find a single contact trajectory inside a given homotopy class, formulated as a single convex optimization problem, and III) how to find a feasible upper body trajectory by solving a set of convex optimization problems.

Regarding future work, we currently work on incorporating our particle planning into a local motion planning algorithm

to produce a dynamical feasible motion. We also would like to investigate when a surface is walkable, depending on physical properties like density, geometry, maximum pressure, and slippage. Finally, we would like to investigate the complexity properties of homotopic particle motion planning.

REFERENCES

[1] S. M. LaValle, Planning Algorithms. Cambridge University Press, 2006. [2] J. H. Reif, “Complexity of the mover’s problem and generalizations,” in Conference on Foundations of Computer Science, pp. 421–427, 1979. [3] A. Orthey, F. Lamiraux, and O. Stasse, “Motion Planning and Irreducible

Trajectories,” in International Conference on Robotics and Automation, 2015.

[4] A. El Khoury, F. Lamiraux, and M. Taix, “Optimal Motion Planning for Humanoid Robots,” in International Conference on Robotics and Automation, 2013.

[5] A. Escande, A. Kheddar, and S. Miossec, “Planning contact points for humanoid robots,” Robotics and Autonomous Systems, vol. 61, no. 5, pp. 428 – 442, 2013.

[6] S. M. Lavalle and J. J. Kuffner Jr, “Rapidly-Exploring Random Trees: Progress and Prospects,” in Algorithmic and Computational Robotics: New Directions, 2000.

[7] L. E. Kavraki, J.-C. Latombe, R. Motwani, and P. Raghavan, “Random-ized query processing in robot path planning,” in Symposium on Theory of Computing, pp. 353–362, ACM, 1995.

[8] S. Bhattacharya, M. Likhachev, and V. Kumar, “Topological constraints in search-based robot path planning,” Autonomous Robots, vol. 33, no. 3, pp. 273–290, 2012.

[9] J.-M. Lien and N. M. Amato, “Approximate convex decomposition of polyhedra and its applications,” Computer Aided Geometric Design, vol. 25, no. 7, pp. 503–522, 2008.

[10] S. Boyd and L. Vandenberghe, Convex Optimization. Cambridge university press, 2004.

[11] B. R. Vatti, “A Generic Solution to Polygon Clipping,” Communications of ACM, vol. 35, pp. 56–63, July 1992.

[12] R. Sedgewick, “Part 5: Graph algorithms,” in Algorithms in C, Addison Wesley Professional, 2001.

[13] W. Rudin, Functional analysis. International Series in Pure and Applied Mathematics, New York: McGraw-Hill Inc., second ed., 1991. [14] B. O’Donoghue, E. Chu, N. Parikh, and S. Boyd, “Operator splitting

for conic optimization via homogeneous self-dual embedding,” arXiv preprint arXiv:1312.3039, 2013.

[15] S. Diamond, E. Chu, and S. Boyd, “CVXPY: A Python-embedded modeling language for convex optimization.” http://cvxpy.org/, May 2014.

[16] K. Kaneko, F. Kanehiro, S. Kajita, H. Hirukawa, T. Kawasaki, M. Hirata, K. Akachi, and T. Isozumi, “Humanoid robot HRP-2,” in International Conference on Robotics and Automation, pp. 1083–1090, 2004. [17] F. Kanehiro, H. Hirukawa, and S. Kajita, “OpenHRP: Open architecture

humanoid robotics platform,” The International Journal of Robotics Research, vol. 23, no. 2, pp. 155–165, 2004.

[18] O. Brock and L. E. Kavraki, “Decomposition-based Motion Planning: A Framework for Real-time Motion Planning in High-dimensional Configuration Spaces,” in International Conference on Robotics and Automation, 2001.

[19] N. Perrin, O. Stasse, F. Lamiraux, and E. Yoshida, “Weakly collision-free paths for continuous humanoid footstep planning,” in International Conference on Intelligent Robots and Systems, 2011.

[20] Y. Yang and O. Brock, “Efficient Motion Planning Based on Disassem-bly,” in Robotics: Science and Systems, (Cambridge, USA), June 2005. [21] V. Ivan, D. Zarubin, M. Toussaint, T. Komura, and S. Vijayakumar, “Topology-based representations for motion planning and generalization in dynamic environments with interactions,” The International Journal of Robotics Research, vol. 32, no. 9-10, pp. 1151–1163, 2013. [22] R. Deits and R. Tedrake, “Footstep Planning on Uneven Terrain with

Mixed-Integer Convex Optimization,” in International Conference on Humanoid Robots, 2014.

[23] M. Farber, “Topological complexity of motion planning,” Discrete and Computational Geometry, vol. 29, no. 2, pp. 211–221, 2003.

Références

Documents relatifs

Induction magnétique Coeff de bobinage du premier harmonique relatif à l’enroulement de l’inducteur Induction dans l'entrefer Induction magnétique de l’aimant Niveau bas des

The rocking of the trunk is possible thanks to the actuation of the hip of the supporting foot. This enables to increase the velocity of the kicking foot at the time of hitting

position and orientation); q ∈ IR n is the robot configuration in an n-dimensional configuration space and x = f (q) is either a point or location attached to the robot expressed

Figure 6.3: Path reshaping considering a dynamic task (a) Three-step strategy applied to the problem of humanoid robot motion generation.. (b) Motion

We showed in Chapter 3, that exploiting the inherent mechanical structure of a robot is essential to an understanding of motion planning. In this chapter, we want to show that

The amounts of MBD2 and MeCP2 transcripts vary greatly between samples in cancer cells compared to normal breast tissues or benign tumors, and in invasive ductal carcinomas the

traitement de la maladie de Freiberg, mais la technique la plus conservatrice et de choix même à un stade avancé reste l’ostéotomie cunéiforme à base dorsale et à

A wedge of open water persisted off the West Coast of Newfoundland (chart of 1st February) until the first week of February when coastal areas north of Port au Port froze over or