Nothing Special   »   [go: up one dir, main page]

Academia.eduAcademia.edu

A combinatorial optimal control problem for spacecraft formation reconfiguration

2007

Proceedings of the 46th IEEE Conference on Decision and Control New Orleans, LA, USA, Dec. 12-14, 2007 FrB07.2 A Combinatorial Optimal Control Problem for Spacecraft Formation Reconfiguration Taeyoung Lee∗† , Melvin Leok∗ , and N. Harris McClamroch† Abstract— We consider a spacecraft formation reconfiguration problem in the case of identical spacecraft. This introduces in the optimal reconfiguration problem a permutational degree of freedom, in addition to the choice of individual spacecraft trajectories. We approach this non-convex optimization problem using a coupled combinatorial and continuous optimization framework, in which the inner loop consists of computing the costs associated with a particular assignment by using a geometrically exact and numerically efficient discrete optimal control method based on Lie group variational integrators. In the outer optimization loop, combinatorial optimization techniques are used to determine the optimal assignments based on the costs computed in the inner loop. The proposed method is demonstrated on the optimal reconfiguration problem for 5 identical spacecraft to go from an inline configuration to one equally spaced on a circle. I. I NTRODUCTION The objective of spacecraft formation control is to use multiple spacecraft for cooperative missions such as orbiting long base-line interferometers. Formation reconfiguration can be classified into two types: (i) each spacecraft is assigned a specified location in the desired reconfigured formation; (ii) a specified location in the desired formation can be occupied by any single spacecraft [1]. In general, a formation is composed of identical spacecraft or groups of spacecraft of the same type, and the total fuel consumption depends on the permutations of the formation reconfigurations as well as the maneuver of each spacecraft. In this paper, we study an optimal spacecraft formation problem integrated with an integer/combinatorial optimization approach for the assignment. Usually in combinatorial optimization problems for multiple agents, the dynamics of each agent is either ignored or simplified into an analytic model [2]. Here, we assume that the motion of each spacecraft evolves on the special Euclidean group SE(3), including both translational dynamics and rotational attitude dynamics under a central gravitational potential. Thus, finding the optimal control inputs on a spacecraft assigned to a fixed desired location is demanding even if the combinatorial assignment optimization problem is not considered. This is an interesting and challenging problem since it requires combining a combinatorial optimization approach and an Taeyoung Lee, and N. Harris McClamroch, Aerospace Engineering, University of Michigan, Ann Arbor, MI 48109 {tylee,nhm}@umich.edu Melvin Leok, Mathematics, Purdue University, West Lafayette, IN 47907 mleok@math.purdue.edu ∗ This research has been supported in part by NSF under grants DMS0504747 and DMS-0726263, and by a grant from the University of Michigan. † This research has been supported in part by NSF under grant CMS0555797. 1-4244-1498-9/07/$25.00 ©2007 IEEE. optimal control method over the non-trivial dynamics of spacecraft evolving on SE(3). There has been some work in the literature on combinatorial optimization for spacecraft formation. The costs for all possible spacecraft assignments are directly compared in [1]. This requires a large computational effort since optimal control problems each of the n! assignments have to be solved for a formation of n spacecraft. In [3], the special structure of a Hamiltonian system is utilized to expedite finding the solutions of optimization problems with varying boundary conditions. But, this requires a solution of the Hamilton-Jacobi partial differential equation. To approximate the cost matrix used in the combinatorial assignment problem, we use the cost entries which have been explicitly computed, and the sensitivities of the cost to construct approximations to the remaining entries. The solution of the optimal control problem for each spacecraft is based on a structure-preserving numerical integrator referred to as a Lie group variational integrator [4]. Combined with an indirect optimization method, the Lie group variational integrator provides a geometrically exact but numerically efficient numerical optimization method [5]. The combinatorial optimization scheme for spacecraft formations that we present has the following important features: (i) dynamics of each spacecraft is nontrivial, (ii) a discrete combinatorial optimization on the permutation group is explicitly integrated into the continuous optimal control problems, and (iii) the problem is formulated and solved in discrete time using a Lie group variational integrator for overall computational accuracy and efficiency. II. L IE G ROUP VARIATIONAL I NTEGRATOR The configuration space for the translational and rotational motion of a rigid body is the special Euclidean group, SE(3) = R3 s SO(3). We denote the attitude, position, angular momentum, and linear momentum of the rigid body by (R, x, Π, γ) ∈ T∗ SE(3). The continuous equations of motion are given by γ (1) ẋ = , m γ̇ = f + uf , (2) Ṙ = RS(Ω), (3) m Π̇ + Ω × Π = M + u , (4) where Ω ∈ R is the angular velocity, and u , u ∈ R3 are the control force in the inertial frame and the control moment in the body fixed frame, respectively. The mass of the rigid body is m ∈ R, and J ∈ R3×3 denotes the moment 5370 3 f m 46th IEEE CDC, New Orleans, USA, Dec. 12-14, 2007 of inertia, i.e. Π = JΩ. The map S(·) : R3 7→ so(3) is an isomorphism between so(3) and R3 defined by the condition S(x)y = x×y for all x, y ∈ R3 . We assume that the potential is dependent on the position and the attitude; U (·) : SE(3) 7→ R. The force and the moment due to the potential are denoted by f, M ∈ R3 , and the expressions can be found in [4]. The dynamics of a rigid body has certain geometric properties such as symplecticity, and momentum and energy preservation, and the configuration space is a Lie group. In contrast, the most common numerical integration methods, including the widely used (non-symplectic) explicit RungeKutta schemes, preserve neither the Lie group structure nor these geometric properties. For example, if we integrate (3) by a typical Runge-Kutta scheme, the quantity RT R inevitably drifts from the identity matrix as the simulation time increases. It is often proposed to parameterize rotations by Euler angles or unit quaternions. However, they have an singularity and ambiguity in expressing the attitude. The Lie group variational integrators, introduced in [4], have the desirable property that they are symplectic and momentum preserving, and they exhibit good energy behavior for an exponentially long time period. They also preserve the Euclidean Lie group structure without the use of local charts, reprojection, or constraints. The Lie group variational integrator on SE(3) is given by h T (Mk + um (5) k )) = Fk Jd − Jd Fk , 2 Rk+1 = Rk Fk , (6)  2  h h (7) fk + ufk , xk+1 = xk + γk + m 2m  h h Πk+1 = FkT Πk + FkT (Mk + um Mk+1 + um k )+ k+1 , 2 2 (8)     h h (9) fk + ufk + fk+1 + ufk+1 , γk+1 = γk + 2 2 where the subscript k denotes the k-th step for a fixed integration step size h ∈ R. The matrix Jd ∈ R3×3 is a nonstandard moment of inertia matrix defined by Jd = 1 2 tr[J] I3×3 −J. The matrix Fk ∈ SO(3) denotes the relative attitude between adjacent integration steps. For given (Rk , xk , Πk , γk ) and control input, (5) is solved to find Fk . Then (Rk+1 , xk+1 ) are obtained by (6) and (7), and (Πk+1 , γk+1 ) are obtained by (8) and (9). This yields a map (Rk , xk , Πk , γk ) 7→ (Rk+1 , xk+1 , Πk+1 , γk+1 ), and this process is repeated. The only implicit part is (5), where the actual computation of Fk is done in the Lie algebra so(3). One of the distinct features of the Lie group variational integrator is that it preserves both the symplectic property and the Lie group structure of the rigid body dynamics. As such, it exhibits substantially improved computational accuracy and efficiency compared with other geometric integrators that preserve only one of these properties such as nonsymplectic Lie group methods [6]. The symplectic property is important even in the case of controlled dynamics, since the dissipation rate of the total energy is typically computed inaccurately by non-symplectic integrators [7]. hS(Πk + FrB07.2 III. O PTIMAL C ONTROL OF A R IGID B ODY ON SE(3) We first summarize a computational approach to solve the optimal control problem for a single rigid body [5]. A. Problem Formulation An optimal control problem is formulated for the maneuver of a rigid body from a given initial configuration (R0 , x0 , Π0 , γ0 ) to a desired configuration (Rd , xd , Πd , γd ) during a given maneuver time N with minimal control inputs. given: (x0 , γ0 , R0 , Π0 ), (xd , γd , Rd , Πd ), N, ( min J = u N −1 X k=0 h h f (uk+1 )T Wf ufk+1 + (um )T Wm um k+1 2 2 k+1 ) such that (xN , γN , RN , ΠN ) = (xd , γd , Rd , Πd ), subject to discrete equations of motion (5)–(9), where Wf , Wm ∈ R3×3 are symmetric positive-definite matrices. B. Computational Approach We solve this optimal control problem using an indirect method; necessary conditions for optimality are obtained by using variational expressions that respect the Lie group structure, and the corresponding two-point boundary value problem is solved by using shooting method. Here we use a modified first-order accurate version of the discrete equations of motion, because it yields a compact form for the necessary conditions. This corresponds to a Lie symplectic Euler method that is symplectically conjugate to a Lie Störmer– Verlet method. Hence, our method has effective order two. Define an augmented performance index as Ja = N −1 X h f h (u )T Wf ufk+1 + (um )T Wm um k+1 2 k+1 2 k+1 k=0   h + λ1,T −xk+1 + xk + γk k m o n 2,T −γk+1 + γk + hfk+1 + hufk+1 + λk  −1 + λ3,T logm(Fk − RkT Rk+1 ) k S   + λ4,T −Πk+1 + FkT Πk + h Mk+1 + um , k+1 k where λik ∈ R3 are Lagrange multipliers, and the matrix logarithm is denoted by logm. The constraint (5) is considered implicitly using a constrained variation. Setting δJa = 0, we obtain necessary conditions for optimality as follows. ufk+1 = −Wf−1 λ2k , λk = −1 4 um k+1 = −Wm λk , ATk+1 λk+1 , (10) (11) λk = [λ1k ; λ2k ; λ3k ; λ4k ] ∈ R12 , and Ak ∈ R12×12 is suitably defined in terms of (Rk , xk , Πk , γk ). The necessary conditions for optimality are expressed in terms of a two-point boundary problem. We use the shooting method [8]. A nominal solution satisfying all of the necessary conditions except the boundary conditions is chosen. The unspecified initial multiplier is updated by successive linearization so as to satisfy the specified terminal 5371 , 46th IEEE CDC, New Orleans, USA, Dec. 12-14, 2007 boundary conditions in the limit. The sensitivities of the specified terminal boundary conditions with respect to the unspecified initial multiplier is obtained by a linear analysis. Let zk ∈ R12 be the variation of the state given by zk = [ζk ; δxk ; δΠk ; δγk ], where ζk ∈ R3 denotes the variation d R exp S(ζk ) = of the rotation matrix as δRk = dǫ ǫ=0 k Rk S(ζk ), and variations for other variables are defined in the usual sense. The linearized equations of motion and the linearized multiplier equation can be written as zk+1 = Ak zk + A12 k δλk , δλk = 21 A12 k , Ak+1 A21 k+1 zk+1 + ATk+1 δλk+1 , (12) (13) 12×12 where ∈R can be computed explicitly. The solution of the linear equations (12) and (13) is given by     11  z0 Φk Φ12 zk k , (14) = δλ0 δλk Φ21 Φ22 k k 12×12 where Φij . k ∈R For the given two-point boundary value problem, z0 = 0 since the initial condition is fixed, and λN is free. Thus, zN = Φ12 N δλ0 . (15) Φ12 N The matrix represents the sensitivity of the terminal state with respect to the initial multipliers. Using this sensitivity, a guess of the initial multiplier is iterated to satisfy the terminal boundary conditions in the limit. Any type of Newton iteration can be applied. We use the Newton-Armijo iteration [9], which is a line search with backtracking algorithm. FrB07.2 moves from a given initial configuration (R0i , xi0 , Πi0 , γ0i ) for i ∈ {1, 2, . . . , n} to a desired target T ∈ R3n during a given maneuver time N , where the superscript i denotes the i-th rigid body. precisely, we assume that the n desired positions  More n xid (θ) i=1 , at which all rigid bodies are located at the terminal maneuver time, are given as functions of parameters θ ∈ Rl . The desired attitude, the linear momentum, and the angular momentum at the terminal time, (Rd , Πd , γd ), are assumed to be fixed and to be the same for all rigid bodies. Since all rigid bodies are identical, there are n! possible combinatorial assignments for n rigid bodies to these n desired locations. Let {aij } be a n × n matrix composed of binary elements {0, 1}, referred to as an assignment or a permutation matrix. Each element of the assignment matrix aij represents the assignment of the i-th rigid body to the j-th desired terminal position xjd . If aij = 1, the i-th rigid body is assigned to the j-th node, and if aij = 0, the ith rigid body is not assigned to theP j-th node. Thus, the Pn n assignment is valid if i=1 aij = 1 for all j=1 aij = i, j. The assignment matrix can be equivalently expressed as a set A = {(i, j)|aij = 1}, and the particular desired points assigned for the i-th rigid body for an assignment A is denoted by Ai ∈ {1, . . . , n}. In other words, for an assignment A, the i-th rigid body is assigned to the Ai -th i desired location, xA d . The target is defined in terms of a parameter θ and an assignment A as follows. n on i T (θ, A) = xA ∈ R3n . d (θ) i=1 C. Properties of Computational Approach The key feature of this computational approach for the optimal control problem of a single rigid body is that it is discretized from the problem definition level using the Lie group variational integrator. This is in contrast to obtaining continuous time necessary conditions, which are discretized to numerically solve the two-point boundary value problem. The main advantage of the shooting method is that the number of iteration variables, the initial Lagrange multipliers, is small. The difficulty is that the extremal solutions are sensitive, and the nonlinearities also make it hard to construct an accurate estimate of sensitivity, perhaps resulting in numerical ill-conditioning. Here, the discrete necessary conditions for optimality preserve the geometric structure of the optimal control problem. Thus, there is no geometrical error introduced by the numerical integration algorithm itself. It turns out that, this computational approach provides a geometrically exact and numerically efficient solution to this nonlinear, non-convex rigid body optimal control problem [5]. IV. O PTIMAL F ORMATION C ONTROL OF R IGID B ODIES A. Problem Formulation We now study an optimal formation control problem for n identical rigid bodies where the dynamics of each body is described by (5)–(9). The objective is to find the optimal control forces and moments such that the group Thus, for a given parameter θ ∈ Rl and a given assignment A, the terminal boundary conditions for all rigid bodies are completely determined. The optimal control problem for a formation of n rigid bodies is formulated as   n n given: (xi0 , γ0i , R0i , Πi0 ) i=1 , ( xid (θ) i=1 , Rd , Πd , γd ), N, ) ( −1 n N X X h m,i T h f,i T f,i m,i (u ) Wf uk+1 + (uk+1 ) Wm uk+1 , min J = u,θ,A 2 k+1 2 i=1 k=0 n on i i i such that (RN , xiN ΠiN , γN ) = (Rd , xA (θ), Π , γ ) , d d d i=1 subject to discrete equations of motion (5)–(9). Since we have neglected the interactions between the rigid bodies, the dynamics of the rigid bodies are only coupled through the terminal boundary conditions. If the parameter θ and the assignment A are prescribed, then the optimal control problems for n rigid bodies can be solved independently using the computational approach presented in Section III. The formation cost is the summation of the resulting costs of each rigid body. Therefore, the optimal formation control problem for multiple rigid bodies consists in finding the optimal value of the parameter and the optimal assignment of rigid bodies among the n! possible assignments. This is similar to the optimal formation reconfiguration problem presented in [10] except that we include the combinatorial assignment problem explicitly in this paper. 5372 46th IEEE CDC, New Orleans, USA, Dec. 12-14, 2007 n B. Optimal Control of Rigid Bodies on SE(3) We first solve the optimal formation control problem assuming that an assignment A is pre-determined and fixed. We use a hierarchical optimal control approach [10]. Since the parameter θ completely defines the terminal configuration for the fixed assignment A, it also determines the corresponding cost by taking the sum of the cost of the optimal trajectories for each rigid body. Thus, the optimization problem can be decomposed into an outer optimization problem to find the optimal value of θ that minimizes the total cost, and an inner optimization problem to find the optimal control inputs for the given value of θ. This is a consequence of the fact that n o ′ min J (u, θ) = min min {J (u, θ)|θ = θ } . (16) ′ u,θ θ u The inner optimization problem is solved by using the computational approach given in Section III. The optimal value of θ is found by using the following parameter optimization method. Sensitivity of the cost: Let ci ∈ R be the P contribution of n the i-th body to the total cost so that J = i=1 ci . Since the control input is expressed in terms of the multiplier by (10), the cost ci is represented as follows. N −1 h X i T (λk ) W λik , c = 2 i k=0 2,i 3,i 4,i where = [λ1,i k ; λk ; λk ; λ k ] ∈ −1 −1 diag[03×3 , Wf , 03×3 , Wm ] ∈ R12×12 . λik R12 and W = Suppose that the variation of the initial condition and the i terminal condition are given by z0i , zN ∈ R12 . Using (14), the corresponding variation of the initial multiplier is given by i i −1 (−Φ11,i δλi0 = (Φ12,i N z0 + zN ). N ) (17) Substituting this into (14), we obtain 22,i 12,i −1 i i i δλik = Φ21,i (−Φ11,i N z0 + zN ). k z0 + Φk (ΦN ) Using this, the variation of the cost ci is given by " N −1 # X 21,i 22,i 12,i −1 11,i i i T δc = h (λk ) W (Φk − Φk (ΦN ) ΦN ) z0i k=0 N −1 X " + h 12,i −1 (λik )T W Φ22,i k (ΦN ) k=0 # i zN . (18) These represent the sensitivities of the optimal costs with respect to the initial condition and the terminal boundary ∂ci ∂ci 1×12 . condition; ∂z i , i ∈ R 0 ∂zN Computational approach: The sensitivity of the total cost with respect to the target parameter is given by n where ∂ci ∂xiN elements of n X ∂ci X ∂ci ∂xAi ∂J d = = , i ∂θ ∂θ ∂θ ∂x N i=1 i=1 (19) ∈ R1×3 is composed of the fourth to sixth ∂ci i ∂zN . FrB07.2 Using this gradient computation, we apply the BroydenFletcher-Goldfarb-Shanno (BFGS) method [9] as follows. 1: 2: 3: 4: 5: 6: 7: 8: 9: 10: Guess an initial parameter θ. Solve the n optimal control problems. Find ∂J ∂θ using (19). while ∂J > ǫ. ∂θ Find a line search direction; D = −H −1 ∂J ∂θ . Perform line search θ = θ + αD. Update the Hessian H. Solve the n optimal control problems. Find ∂J ∂θ using (19). end while Here ǫ denotes a stopping criterion and α is a scaling factor, respectively. The Hessian can be initialized with H = Il×l and updated during the BFGS iterations. C. Assignment Optimization Problem Now, we solve the optimal formation control problem assuming that the target parameter fixed. For the given  θ is n value of θ, the n desired points xid i=1 , at which all rigid bodies are located at the terminal time, are completely defined. Thus, there are n! possible combinatorial assignments.  Let cij be a n × n matrix, referred to as a cost matrix. Each element cij represents the optimal cost of the i-th rigid body transferred to the j-th desired location. For Pn an assignment {aij }, the total cost is given by J = i,j=1 cij aij . The optimal assignment problem is given by min aij Pn n X cij aij , i,j=1 Pn subject to j=1 aij = 1, i=1 aij = 1, and aij ∈ {0, 1} for all i, j ∈ {1, 2, . . . , n}. Since we assume that there is no interaction between rigid bodies, the cost matrix is independent of the assignment. For the given value of the target parameter θ, we must solve at most n2 optimal control problems to obtain the cost matrix. Once we have the complete cost matrix, the optimal assignment can be obtained by comparing costs for all possible assignments or by using the Hungarian method [11]. It is often expensive to obtain the cost matrix. Each element of the cost matrix is a solution of the optimal control problem presented in Section III. For the formation optimization problem, we need to find the cost matrix with varying values of the target parameter θ. Thus, the objective of this subsection is to find the optimal assignment without solving all n2 optimal control problems. We start with an initial single spacecraft optimal trajectory computation, and use its optimal cost and the sensitivities given in (18) to populate the remaining entries of the cost matrix. Suppose that we solve the optimal control problem for the first rigid body transferred to the first desired point to obtain c11 . Since this optimal solution is obtained by computing the linearized equations in (14). we can find the sensitivity of the cost with respect to the terminal boundary condition ∂c11 ∂xd using (18), without need of additional computational 5373 46th IEEE CDC, New Orleans, USA, Dec. 12-14, 2007 FrB07.2 TABLE I M ETHODS TO CHOOSE SENSITIVITIES burden. Then, the optimal cost of transferring the first body to another desired point, say xd , is approximated as ĉ1 (xd ) = c11 + 1 ∂ 2 c11 ∂c11 ∆xd + (∆xd )T ∆xd , (20) ∂xd 2 ∂(xd )2 where ∆xd = xd − x1d ∈ R3 . The first-order sensitivity is ∂ 2 c11 computed exactly, and the second-order Hessian ∂(x 2 is d) initially set to zero, and the approximation is improved as other optimal solutions become available. For example, if the solution of the optimal control problem of the first rigid body transferred to the second desired point is found, we obtain 12 the exact value of c12 and ∂c ∂xd . This provides the following 1 and 3 dimensional constraints on the Hessian ∂c12 ∂ĉ1 . = ĉ1 (x2d ) = c12 , ∂xd xd =x2 ∂xd d Thus, the 6 elements of the Hessian can be approximated in either the minimum norm or least-squares sense if additional optimal solutions involving the first rigid body are available. This approach approximates the elements of the cost matrix along rows using the sensitivity of the cost with respect to terminal boundary values. A similar approximation along columns can be made by using the sensitivity of the cost with respect to the initial values. In the combinatorial optimization process, we utilize both approximations in order to avoid local minima. The advantage is that we use all of the sensitivity information available up to the current iteration in order to estimate the new cost matrix. We construct a combinatorial assignment method using these approximations. i) Guess an initial assignment and solve the corresponding optimal control problems for this assignment. ii) Estimate the cost matrix using the linear approximations. iii) Find a new assignment using the estimated cost matrix, and solve the corresponding optimal control problems for this assignment. iv) Find the best assignment using all of the solutions of the optimal control problems obtained so far. v) Construct a second-order approximation (20) based on the best assignment, and estimate the cost matrix. vi) Repeat (iii)-(v) until the same approximation is repeated r times in a row at (v). Larger value of r tends to find the global optimal assignment, but longer computation time is required. At Steps (ii) and (v), we construct the approximation to the cost matrix using either the sensitivity of the cost with respect to the initial values or the sensitivity of the cost with respect to the terminal values. Several ways are summarized in Table I. Numerical simulations demonstrate that using both types of sensitivities has advantages and the last method is more efficient than the others in terms of finding the global optimal assignment with minimal computational effort for a fixed θ. D. Computational Approach for Optimal Formation Control We have presented two optimization approaches; finding the optimal value of the target parameter for a given assign- Method Term. Init. Rand. Rpt. Alt. Comp. Sensitivity Selection Use terminal sensitivity always. Use initial sensitivity always. Choose one of sensitivities randomly. If the same assignment is repeated twice, switch to using a different sensitivity. Alternate sensitivities. For each element of the cost matrix, compare the number of available solutions along the row direction, and the number of available solutions along the column direction. Select sensitivities along the direction that has more available solutions. ment, and finding the optimal assignment for a given value of the target parameter. We integrate both methods using a hierarchical optimization approach similar to (16). The original optimization problem is stated as finding the optimal control forces, moments, target parameter, and assignment that minimizes the total cost. min J (u, θ, A). u,θ,A Equivalently, this can be stated as finding the optimal assignment over the optimal control inputs and the target parameter:   ′ min min {J (u, θ, A)|A = A } . ′ A u,θ In the inner stage, we optimize the target parameter and the control inputs using the continuous optimization approaches presented in Section IV-B, and in the outer stage, we find the optimal assignment using the combinatorial optimization approach presented in Section IV-C. The optimization process is terminated when the iterations yield a solution that is optimal for both the continuous and combinatorial optimization stages. V. N UMERICAL E XAMPLE We study a maneuver involving 5 identical rigid spacecraft orbiting in a central gravity field. Each spacecraft is modeled as a dumbbell, which consists of two equal spheres and a massless rod [5]. The spacecraft are initially aligned along a radial direction as shown in Fig. 1(a). At the terminal time, we require that the spacecraft are equally distributed on a target circle described by the location of its center x◦ ∈ R3 , the radius r◦ ∈ R, and the unit normal vector n◦ ∈ S2 . Let θi ∈ S1 be the angle of the i-th spacecraft on the target circle as shown in Fig. 1(b). We choose the target parameter as the angle of the first rigid body. The target T is given by  n T (θ1 , A) = x◦ + r◦ cos θi e1 + r◦ sin θi e2 i=1 , where e1 = kxx◦◦ k , e2 = e1 × n◦ are unit vectors in the target plane, and the angle θi is chosen to distribute the spacecraft uniformly on the circle, i.e. θi = θ1 + 2π/5(Ai − i). Since the target parameter θ1 determines the terminal position of the first spacecraft completely, we require that 5374 46th IEEE CDC, New Orleans, USA, Dec. 12-14, 2007 FrB07.2 Terminal formation e2 Initial formation θi i-th body e1 (a) The initial formation and the (b) The terminal formation on a tarterminal formation get circle Fig. 2. Fig. 1. The initial formation and the desired terminal formation of 5 dumbbell spacecraft on a circle Optimal spacecraft formation reconfiguration maneuver 14 Number of optimal solutions 250 the first spacecraft be assigned to the first desired location, i.e. A1 = 1. There remain 4! assignments for the other four spacecraft. Thus, the optimization parameters are the angle of the first spacecraft on the target circle, the 4! assignments for the remaining spacecraft, and the control inputs. The iteration procedure for a particular numerical implementation of the optimization are shown as follows with computation time on an Intel Pentium M 1.73GHz processor using MATLAB. i) The initial guess of the assignment is given by A = {(1, 1), (2, 4), (3, 2), (4, 3), (5, 5)}. ii.a) For the given assignment, the optimal value of θ1 = 2.4520 is obtained in 48.32 minutes with J = 8.6984. ii.b) For the given value of θ1 , the optimal assignment of A = {(1, 1), (2, 5), (3, 2), (4, 3), (5, 4)} is obtained in 3.04 minutes with cost J = 8.6905. ii.c) For the given θ1 and the given assignment, we check ∂J −2 . Repeat iteration. ∂θ 1 = 2.42 × 10 iii.a) For the given assignment, the optimal value of θ1 = 2.5084 is obtained in 12.69 minutes with J = 8.6898. iii.b) For the given value of θ1 , the same optimal assignment of A = {(1, 1), (2, 5), (3, 2), (4, 3), (5, 4)} is obtained in 2.98 minutes with cost J = 8.6898. iii.c) For the given θ1 and the corresponding optimal assign∂J −5 . ment, we check ∂θ 1 = 9.99 × 10 iv) The optimization is terminated in 67.03 minutes with J = 8.6898 for θ1 = 2.5084 and A = {(1, 1), (2, 5), (3, 2), (4, 3), (5, 4)}. The corresponding maneuvers for the spacecraft are shown in Fig. 2. At each iteration, we use the optimization data accumulated in the previous iterations in order to initialize the initial multiplier value for the optimal control problems. This reduces the computation time as the iterations proceed. In order to estimate the distribution of all possible solutions, we uniformly discretize the interval [0, 2π) by 100 points for the target parameters and we find the total costs of 4! assignments for each value of the target parameter. The histogram for total costs of the corresponding 100 × 4! = 2400 solutions is shown in Fig. 3(a). Numerical simulations show that the optimized solution obtained depends more strongly on the initial guess of the assignment than the initial guesses for the target parameter and the initial multiplier value. We repeat the numerical opti- Number of solutions 200 150 100 50 0 8.65 8.7 8.75 Cost 8.8 8.85 8.9 12 10 8 6 4 2 0 8.65 8.7 8.75 Cost 8.8 8.85 8.9 (a) Histogram of total costs for 2400 (b) Histogram of total cost for 24 opsolutions with varying target parame- timized solutions with varying initial ters and assignments guesses of assignment Fig. 3. Distribution of the total costs before and after optimization mization for all possible 4! initial guesses of the assignment. Fig. 3(b) shows the histogram of the optimized total costs for varying initial assignment. Six initial assignments converged to the optimal solution with the minimal cost J = 8.6898 in the pre-computed 100 × 4! = 2400 solutions; this is assumed to be the global optimal solution. Seven initial assignments converged to a local optimal solution close to the global optimal solution with J = 8.6985. R EFERENCES [1] P. K. C. Wang and F. Y. Hadaegh, “Minimum-fuel formation reconfiguration of multiple free-flying spacecraft,” Journal of the Astronautical Sciences, vol. 47, no. 1-2, pp. 77–102, 1999. [2] K. Savla, F. Bullo, and E. Frazzoli, “On traveling salesperson problems for a double integrator,” in Proceedings of the IEEE Conference on Decision and Control, 2006, pp. 5305–5310. [3] V. M. Guibout and D. J. Scheeres, “Spacecraft formation dynamics and design,” Journal of Guidance, Control, and Dynamics, vol. 29, no. 1, pp. 121–133, 2006. [4] T. Lee, M. Leok, and N. H. McClamroch, “Lie group variational integrators for the full body problem,” Computer Methods in Applied Mechanics and Engineering, vol. 196, pp. 2907–2924, 2007. [5] ——, “Optimal control of a rigid body using geometrically exact computations on SE(3),” in Proceedings of the IEEE Conference on Decision and Control, 2006, pp. 2170–2175. [6] ——, “Lie group variational integrators for the full body problem in orbital mechanics,” Celestial Mechanics and Dynamical Astronomy, vol. 98, pp. 121–144, 2007. [7] J. E. Marsden and M. West, “Discrete mechanics and variational integrators,” Acta Numerica, vol. 10, pp. 357–514, 2001. [8] A. E. Bryson and Y.-C. Ho, Applied Optimal Control. Hemisphere Publishing Corporation, 1975. [9] C. T. Kelley, Iterative Methods for Linear and Nonlinear Equations. SIAM, 1995. [10] O. Junge, J. E. Marsden, and S. Ober-Blöbaum, “Optimal reconfiguration of formation flying spacecraft a decentralized approach,” in Proceedings of the IEEE Conference on Decision and Control, 2006, pp. 5210–5215. [11] K. G. Murty, Linear and combinatorial programming. Wiley, 1985. 5375