1 Introduction

Attitude motion planning is necessary in mission scenarios in which a spacecraft must perform large angle maneuvers with the additional requirement that sensitive instruments must not point to bright celestial objects. These so-called keep-out cones define constraints that must be satisfied along the instrument trajectory. This research presents a control synthesis method for constructing an appropriate control torque that achieves the desired rest-to-rest maneuver and ensures that the keep-out cones are avoided. The angular velocity is expressed as weighted sum of some basis functions, and the weights are obtained by solving a constrained minimization problem in which the objective is the maneuvering time.

Most of existing methods for attitude motion planning with keep-out cones can be classified into the following four main groups, see also [24, 27]. One group uses path planning methods to search for a path from the initial attitude to the final attitude avoiding the keep-out cones. Path planning is performed by first operating a discretization, and then by searching for a feasible path by employing either a graph search algorithm [14, 33, 34] or a random search method [11]. Both search methods can become computationally demanding. A different group of methods is based on trajectory optimization algorithms in which the constrained attitude motion planning problem is formulated as an optimal control problem. The obtained optimization problems are nonconvex, and their solution is determined either by indirect methods [16], or by gradient-based techniques [9], or by global optimizers [4, 21, 29, 30, 32], or by employing a convexification method [13]. This second group of methods might have a high computational cost, too. In the third group, geometric relations are used to determine trajectories that avoid the keep-out cones [2, 12]. These methods are simpler but can be used effectively only with a small number of keep-out cones. The last group of techniques is based on potential functions that have a minimum at the desired attitude and large values around the exclusion cones. The potential function is employed to design a control law based either on Lyapunov theory [1, 15, 20, 22, 24, 26, 27] or on optimal control [31]. Those methods are less computationally demanding. However, the spacecraft might get trapped into local minima of the potential function or other critical points.

In some of the cited works, attitude is represented using Euler angles [12, 20, 22] which are defined only locally and exhibit kinematic singularities which can limit the width of the maneuvers. In most of them [1, 4, 13, 14, 21, 24, 26, 29, 32, 34], quaternions are employed. Quaternions are free of singularities but present ambiguity in representing attitude. Thus, boundary conditions for the spacecraft attitude do not have a unique representation in quaternions. Consequently, a quaternion-based motion planning may exhibit the undesired unwinding behavior [10]. In other works, attitude is represented by modified Rodrigues parameters [26, 27, 30], which are both singular and nonunique. It is possible to employ modified Rodrigues parameters avoiding singularities by taking advantage of the nonuniqueness, and also overcoming the unwinding phenomenon. However, using those methods makes the attitude representation quite complex. In some works, including this one, attitude is represented on the special orthogonal group SO(3) [2, 9, 11, 15, 16, 31, 33] which is a global, unique, nonsingular, but nonminimal parametrization. However, nonminimality does not represent an issue when open-loop control torques are designed as in the present research.

In this work, spacecraft attitude motion planning is performed on SO(3) by minimizing the maneuvering-time after having expressed the angular velocity as linear combination of some appropriate basis functions. The corresponding weights are determined through a derivative-free optimization method. The approach of expressing kinematic magnitudes as linear combination of some basis functions has been widely adopted in motion planning methods [3, 4, 8, 23, 35]. The main benefit of adopting in this work a basis function expansion for the angular velocity is the possibility of determining a control torque that is continuously differentiable and that vanishes at initial and final time. This property makes the torque easier to implement than control torques obtained with other methods that do not vanish at their endpoints and are sometimes discontinuous during the maneuver [4, 21, 29]. Indeed, the available torque actuators might not be able to generate control torques that change too rapidly. On the other hand, since the angular velocity is constrained to be the linear combination of certain basis functions, the maneuvering time achieved with the proposed method is likely to be longer than with methods [4, 21, 29] where such constraint is not enforced.

An important aspect of derivative-free optimization techniques is that first order information on the objective function and on the constraints are not needed. For this reason, different derivative-free methods have already been used to successfully solve other attitude control problems [5, 6]. In practice, derivative-free techniques do not even need the analytical expression of objective function or constraints; they only need to compute them in a number of points by using simulations. Thus, the method presented in this work represents an improvement of the one in [9] for the following aspects. In [9] a gradient-based optimization was employed to find the weights. However, since it was not possible to determine expressions for the gradients of the objective and of the constraints, both the objective and the constraints were replaced by approximations for which it was possible to compute the corresponding gradients. Since in this work the gradients are not needed, the objective and constraints are considered in their original exact form.

However, the optimization of this exact problem turns out to be particularly demanding, since there is a large number of local minima, and the problem is very numerically sensitive. To overcome these issues, we propose a new optimization technique based on the alternation of two objective functions during the search. Objective perturbation techniques have been often used in global optimization to escape local minima, see for example tunneling [17] or filled functions [19]. The basic idea is to temporarily modify the objective function until the local minimum is escaped, or to slightly change it so to have less local minima. In our case, we have both the original objective (maneuvering time) and the approximating differentiable objective proposed in [9] (sum of the squared weights). Hence, we can think of temporarily switching from the first objective to the second one to escape the local minima, still within the framework of the same derivative-free algorithm. This operation is able to completely change the optimization “landscape” without the need of explicitly computing a gradient even for the second objective.

The remaining of this work is organized as follows. Section 2 describes the attitude motion planning problem; Sect. 3 presents the proposed optimization technique; Sect. 4 provides numerical results on two interesting case studies already considered in the literature.

2 Problem Statement

In the spacecraft attitude motion planning problem on SO(3), the initial attitude \(\mathbf {\mathbf {R_i } }\in \) SO(3) and the desired final attitude \(\mathbf {R_f} \in \) SO(3) are given, and both the initial angular velocity and the desired final angular velocity must be zero (rest-to-rest maneuver). The attitude \(\mathbf {R}(t) \in \) SO(3) is subject to the attitude kinematics \( \dot{\mathbf {R}} = \mathbf {R} \, \varvec{\omega }^{\times } \) where \( \varvec{\omega }^{\times } = \omega _1 \mathbf {A_1} + \omega _2 \mathbf {A_2} + \omega _3 \mathbf {A_3}\) in which \(\omega _1\), \(\omega _2\), and \(\omega _3\) are the components of the spacecraft angular velocity along body axes and

$$\begin{aligned} \mathbf {A_1}=\left[ \begin{array}{ccc}0 &{} 0 &{} 0 \\ 0 &{} 0 &{} -1 \\ 0 &{} 1 &{} 0\end{array}\right] \ \ \ \mathbf {A_2}=\left[ \begin{array}{ccc}0 &{} 0 &{} 1 \\ 0 &{} 0 &{} 0 \\ -1 &{} 0 &{} 0\end{array}\right] \ \ \ \mathbf {A_3}=\left[ \begin{array}{ccc}0 &{} -1 &{} 0 \\ 1 &{} 0 &{} 0 \\ 0 &{} 0 &{} 0\end{array}\right] . \end{aligned}$$

The relation between \(\varvec{\omega }=[\omega _1 \ \omega _2 \ \omega _3]^T\) and the control torque resolved in body frame \(\mathbf {T}\) is given by the attitude dynamics \( \mathbf {J} \dot{\varvec{\omega }} + \varvec{\omega } \times \mathbf {J} \varvec{\omega } =\mathbf {T} \), in which \(\mathbf {J}\) is the spacecraft inertia matrix. Disturbance torques are neglected. Denote with \(\bar{T}\) the maximum amplitude of \(T_j\) for \( j=1,2,3\) due to actuator constraints. The spacecraft is equipped with an on-board sensor whose pointing direction in body coordinates is given by unit vector \(\mathbf {r}\). There are C undesired pointing directions for the sensor which are specified in inertial coordinates by unit vectors \(\mathbf {w}_i \ \ i=1,\ldots ,C\). For example, \(\mathbf {r}\) can be the pointing direction in body coordinates of an on-board optical sensor, and \(\mathbf {w}_i\) is the inertial direction of a bright celestial object. It is required that the boresight of the sensor avoids inertial direction \(\mathbf {w}_i\) with a minimum offset angle \(0< \theta _{i} <90^{\circ }\). Thus, the following constraints are introduced

$$\begin{aligned} \mathbf {r}^T \mathbf {R}(t)^T \mathbf {w}_i \le \cos \theta _{i} \ \ \ \ \ i=1,\ldots ,C . \end{aligned}$$
(1)

Given the initial conditions \(\mathbf {R}(0)=\mathbf {R_i} \ \ \varvec{\omega }(0)=\mathbf {0}\), we search for a control torque \(\mathbf {T}(t)\) defined over a finite interval \([0 \ \ t_f]\) that fulfills the amplitude constraints

$$\begin{aligned} |T_j(t)| \le \bar{T} \ \ \ \ \ j=1,2,3 \ \ \ \ 0 \le t \le t_f \end{aligned}$$
(2)

and is such that attitude \(\mathbf {R}(t)\) and angular velocity \(\varvec{\omega }(t)\) satisfy the final conditions \(\mathbf {R}(t_f)=\mathbf {R_f} \ \ \varvec{\omega }(t_f)=\mathbf {0}\) and the pointing constraints (1). In addition, the control torque must be continuously differentiable, must vanish at \(t=0\) and \(t=t_f\), and must minimize the maneuvering time \(t_f\).

3 Attitude Motion Planning Using Derivative-Free Optimization

In the initial phase of our approach we use normalized time \(\tau =t/t_f\) , as in [2]. Clearly, \(0 \le \tau \le 1\). Afterwards, when \(t_f\) is obtained, we can switch to actual time to obtain the control torque. The angular velocity in normalized time \(\varvec{\omega }^*(\tau )\) is expressed as follows for a set of M continuously differentiable basis functions \(v_k(\tau ) \ \ k=1,\ldots ,M\).

$$\begin{aligned} \omega _j^*(\tau ) = \sum _{k=1}^M \alpha _{jk} v_k(\tau ) \ \ \ \ j=1,2,3 \end{aligned}$$
(3)

The basis functions must fulfill the following end-point conditions: \(v_k(0)=v_k(1)=0\), so that we have \(\varvec{\omega }^*(0)=\varvec{\omega }(1)^*=\mathbf {0}\) as required. The basis functions must also fulfill the additional end-point conditions \(\dfrac{d v_k}{d \tau }(0) = \dfrac{d v_k}{d \tau }(1) = 0\), so that \(\varvec{\omega }^*(\tau )\) satisfies \(\dfrac{d \varvec{\omega }^*}{d \tau }(0) = \dfrac{d\varvec{\omega }^*}{d \tau }(1) = \mathbf {0}\). This will ensure that the control torque \(\mathbf {T}(t)\) has the property \(\mathbf {T}(0)=\mathbf {T}(t_f)=\mathbf {0}\), as it will be clear later on.

The weights \(\alpha _{jk}\) in Eq. (3) must be chosen so that the following constraints are fulfilled. Denote the attitude in normalized time by \(\mathbf {R}^*(\tau )\) which is obtained from \(\varvec{\omega }^*(\tau )\) through the following kinematics equation in normalized time

$$\begin{aligned} \frac{d \mathbf {R}^*}{d \tau }(\tau ) = \mathbf {R}^*(\tau ) (\varvec{\omega }^{* \times }(\tau )) \end{aligned}$$
(4)

with initial condition \(\mathbf {R}^*(0)=\mathbf {R_i}\), where \(\varvec{\omega }^{* \times }\) is defined analogously to \(\varvec{\omega }^{\times }\). Thus, achieving the desired final attitude is enforced by the following equality constraint

$$\begin{aligned} \mathrm {tr} \left[ \mathbf {R}^T_f \mathbf {R}^*(1) \right] =3 \end{aligned}$$
(5)

where tr denotes the trace of a matrix. In addition, exclusion cones are avoided by adding the following inequality constraints [see Eq. (1)]

$$\begin{aligned} \mathbf {r}^T \mathbf {R}^*(\tau )^T \mathbf {w}_i \le \cos \theta _{i} \ \ \ i=1,\ldots ,C \ \ \ 0 \le \tau \le 1 . \end{aligned}$$
(6)

Those inequality constraints are enforced numerically by adopting the following approach. Discretize the interval \([0\, 1]\) into N equal segments defining \(\varDelta \tau = 1/N\) and \(\tau _\ell =(\ell -1) \varDelta \tau \ \ \ell =1,\ldots ,N+1\). Inequality constraints are enforced only at the discrete times \(\tau _{\ell }\) obtaining

$$\begin{aligned} \mathbf {r}^T \mathbf {R}^*(\tau _{\ell })^T \mathbf {w}_i \le \cos \theta _{i} \ \ \ \ \ell =1,\ldots ,N+1 \ \ \ i=1,\ldots ,C . \end{aligned}$$
(7)

For fixed weights \(\alpha _{jk}\) that fulfill the previous equality and inequality constraints, the angular velocity in normalized time \(\varvec{\omega }^*(\tau )\) is obtained. Thus, the control torque \(\mathbf {T}(t)\) and the maneuvering time \(t_f\) are determined as follows. As in [2], from the angular velocity in normalized time, the control torque in normalized time can be obtained from the attitude dynamics as

$$\begin{aligned} \mathbf {T}^*(\tau )=\mathbf {J} \frac{d \varvec{\omega }^*}{d \tau }(\tau ) + \varvec{\omega }^*(\tau ) \times \mathbf {J} \varvec{\omega }^*(\tau ) \ \ 0 \le \tau \le 1 . \end{aligned}$$
(8)

From the control torque in normalized time \(\mathbf {T}^*(\tau )\), the maneuvering time \(t_f\) can be determined as follows. Compute \( \overline{T^*}= \max _{0 \le \tau \le 1 \ j=1,2,3} | T^*_j(\tau )| \) which numerically is determined as follows

$$\begin{aligned} \overline{T^*}= \max _{\ell =1,\ldots ,N \ j=1,2,3} | T^*_j(\tau _{\ell })| \end{aligned}$$
(9)

and set

$$\begin{aligned} t_f=\sqrt{\overline{T^*}/ \bar{T}} . \end{aligned}$$
(10)

The latter value of \(t_f\) enforces the fulfillment of the amplitude constraints in Eq. (2). In fact, consider the actual time \(t=\tau t_f\), consequently \(\mathbf {R}(t)=\mathbf {R}^*(t/t_f) \ \ 0 \le t \le t_f\). It is immediate to see that the angular velocity is given by \(\varvec{\omega }(t)=1/t_f \ \varvec{\omega }^*(t/t_f) \ \ 0 \le t \le t_f\). Moreover, it is easy to obtain that the control torque is equal to \( \mathbf {T}(t)= \frac{1}{t_f^2} \mathbf {T}^*\left( \frac{t}{t_f} \right) \ \ 0 \le t \le t_f . \) Consequently, from the equation above it follows that the value of \(t_f\) in Eq. (10) guarantees the fulfillment of the amplitude constraints on the control torque.

The goal is minimizing the maneuvering time \(t_f\). This can be achieved by solving a minimization problem in which the decision variables are the weights \(\alpha _{jk}\) in Eq. (3), the objective function is the maneuvering time \(t_f\) in Eq. (10), and \(\alpha _{jk}\) are subject to the equality constraint in Eq. (5) and the inequality constraints in Eq. (7). The relation between \(\mathbf {R}^*(\tau )\) and \(\varvec{\omega }^*(\tau )\) is given by Eq. (4) with initial condition \(\mathbf {R}^*(0)=\mathbf {R_i}\). By writing the set of the \(\alpha _{jk}\) weights as \(\varvec{\alpha }\), the structure of this constrained optimization problem, denoted by CP, can be represented with the following model (11). The dependency on the set \(\varvec{\alpha }\) is only indicated implicitly. The equality constraint is briefly denoted as EC, whereas the inequality constraints are \(\mathrm{IC}_{\ell , i}\) with \(\ell =1,\ldots ,N+1\) and \( i=1,\ldots ,C\).

$$\begin{aligned} \begin{array}{l} \min \ t_f({\varvec{\alpha }}) \\ \mathrm{EC}({\varvec{\alpha }})\\ \mathrm{IC}_{\ell , i}({\varvec{\alpha }}) \ \ \ \ \ell =1,\ldots ,N+1, \ \ \ i=1,\ldots ,C \\ \end{array} \end{aligned}$$
(11)

However, the above problem has a main difficulty. Both in the objective function and in the constraints EQ and \(\mathrm{IC}_{\ell , i}\), the dependency on the optimization variables \(\varvec{\alpha }\) cannot be expressed in analytical form. Hence, an explicit optimization model cannot be written for CP. To solve it despite this issue, a derivative-free optimization approach is adopted. This solution approach needs no gradient expression of objective function or constraints. In practice, this type of algorithms does not even need the analytical expression of the optimization model, they only need to be able to evaluate the objective function and the constraints of the optimization problem over a number of points. Since in our case the analytical expression of the model are not available, those evaluations can be obtained by using simulations which take as input a set of values \(\varvec{ \bar{\alpha }}\) and provide the numerical evaluations of \( t_f(\varvec{ \bar{\alpha }})\), \(\mathrm{EC}({\varvec{ \bar{\alpha }}})\), and \(\mathrm{IC}_{\ell , i}({\varvec{ \bar{\alpha }}})\) for \(\ell =1,\ldots ,N+1\) and \( i=1,\ldots ,C\).

Due to the constrained nature of CP and its size and features, we select as solution algorithm the derivative-free sequential penalty method proposed in [18]. In standard nonlinear optimization, a sequential penalty approach consists in solving the original constrained problem by a sequence of approximate minimizations of an unconstrained merit function where the violation of the original constraints is penalized, and this penalization is progressively increased in order to end up with a solution which is feasible for the original constrained problem. The selected algorithm extends the described sequential penalty approach to the derivative-free context. In particular, such an algorithm is able to guarantee convergence to a stationary point of the constrained problem, by locally exploring the behavior of the merit function corresponding to variations in the optimization variables. This is obtained in practice by means of an iterative algorithm evaluating the merit function over a sequence of points \((\varvec{ \bar{\alpha }}_1, \varvec{ \bar{\alpha }}_2,\dots )\). The iterations are interrupted either when the improvements become numerically negligible or when the maximum number of iterations is reached.

Unfortunately, problem CP has another main difficulty. The feasible region contains a very large number of local minima, and the sequence of points obtained by the solution algorithm may very likely be attracted and subsequently get stuck in one of them. However, in the practical application, we are only interested in aiming at an optimal or suboptimal solution. Note, moreover, that CP is also very sensitive from the numerical point of view, in the sense that small variations in the optimization variables \(\varvec{\alpha }\) may determine huge variations in the value of the cost function.

To overcome these problems, we propose a new optimization technique based on an alternation of two objective functions. Objective perturbation techniques have been often used in global optimization to escape local minima, because a perturbation is able to change the function “landscape”. In the case of problem CP, besides the original objective given by the maneuvering time \(t_f\), reported in (11), we can consider an approximating objective given by the sum of the squared alphas:

$$\begin{aligned} \sum _{j=1}^3 \sum _{k=1}^M \alpha _{jk}^2 \end{aligned}$$
(12)

Indeed, small values for the alphas will approximatively decrease \(t_f\), as already noted in [9]. Hence, when the optimization algorithm gets stuck in a local minimum of the objective \(t_f\) in (11), we temporarily switch from this objective to objective (12), and this can be done while continuing with the iterations of the selected derivative-free algorithm. Note that the constraints remain the same, so the parts of the merit function given by them remains constant. However, this operation will in general completely change the optimization “landscape”, and a local minimum for the first objective will not, very likely, be a local minimum for the second objective. Hence, the sequence of points evaluated by the optimization algorithm will escape from the local minimum of the objective \(t_f\). Maintaining the derivative-free framework while pursuing the second objective has also the advantage of not needing an explicit computation of the gradient even for the second objective, making it less attracted by local minima. After some iterations with the second objective (either a fixed number of iterations or until a condition on the values of the \(\alpha _{jk}\) is reached), our algorithm switches back to the first objective, and so on. The alternation of the two objectives is repeated until a satisfactory solution is obtained.

The described technique can also be seen as an evolution of the well known multi-start approach, since the optimization with one objective is performed by starting from several different points (the ending points of the phases with the other objective). However, differently from classical multi-start techniques, those starting points are selected by applying some “intelligence” and not simply at random or with other predetermined schemes.

4 Numerical Results

We apply the derivative-free solution strategy described above to solve two difficult case studies already considered in the literature.

4.1 Case Study 1

The first case study has been presented in [29]. Consider a satellite for Earth observation in low Earth orbit. A typical maneuver for the satellite to perform Earth observation is switching between pointing to one side of the ground-track to pointing to its opposite side. Such maneuver corresponds to a roll rotation. Assume that the required roll rotation is 135 deg wide. Thus, setting the initial attitude as \(\mathbf {R_i }=\mathbf {I}_{3 \times 3}\), the desired final attitude is equal to \(\mathbf {R_f}=\exp (3/4 \pi \mathbf {A_1})\). The satellite is equipped with a start tracker that must avoid sun and moon directions with prescribed offset angles during the maneuver. The pointing direction of the star tracker sensor is expressed in body coordinates by the following unit vector \(\mathbf {r}=[0 \ 1 \ 0 ]^T\). The two keep-out cones are specified as follows: 1) sun cone with inertial direction \(\mathbf {w}_1=[-0.18 \ 0.56 \ 0.81]^T\) and minimum offset angle \(\theta _1=47\) deg; 2) moon cone with inertial direction \(\mathbf {w}_2=[0.95 \ 0 \ 0.31]^T\) and minimum offset angle \(\theta _2=36\) deg.Footnote 1 The satellite inertia matrix is given by \(\mathbf {J}=\mathrm {diag}[3000\ 4500\ 6000] \ \mathrm {kg\ m}^2\). The maximum torque along each body axis is equal to \(\bar{T}\)= 0.25 N m.

As done in [9], in this case study the basis functions \(v_k(\tau )\) have been defined only at the discrete times \(\tau _{\ell } \ \ell =1,\ldots ,N\) and have been chosen as the so-called Slepian sequences [28]. These sequences are parameterized by their length N and the half-bandwidth parameter \(W \in \ ]0 \ 0.5[\). In this case study, the first \(M=4\) Slepian sequences with \(N=500\) and \(W=0.015\) have been considered. The values of M, N, and W have been determined by a trial-and-error approach based on the following considerations. The larger M, the larger the number of basis functions for \(\omega ^*_j(\tau ) \ j=1,2,3\) [see Eq. (3)]. Consequently, increasing M expands the possible time behaviors for \(\omega _j^*(\tau ) \ j=1,2,3\), and this could in theory allow to obtain smaller values of the minimum maneuvering time \(t_f\). On the other hand, since the number of decision variables \(\alpha _{jk}\) is equal to 3M, the larger M, the larger the number of dimensions of the feasible set of the optimization problem (11). As a result, computational load could greatly increase. Moreover, as the dimensionality increases, the numerical accuracy can only be reduced, and since this problem is particularly numerically sensitive, this behavior should be avoided. In conclusion, numerical experiments show that the value \(M=4\) represents a good trade-off between those conflicting demands. Regarding parameter N, clearly the larger N, the more accurate the approximation in Eq. (7) of the original inequality constraints in Eq. (6). On the other hand, if N increases, so does the number of inequality constraints of the optimization problem (11), which leads again to an increase in the computational burden. It turns out that, for the current case study, \(N=500\) provides a good balance. Finally, \(W \in \ ]0 \ 0.5[\) has been selected as follows. If W is close to 0, the Slepian sequences do not vanish at the endpoints. Consequently, selecting W too close to 0 would lead to angular velocities that do not vanish at the initial and final time, and the maneuver would not be rest-to-rest. If W is close to 0.5, the Slepian sequences quickly become approximately equal to 0 and keep such values for long intervals after \(\tau =0\) and before \(\tau =1\). Thus, if W is close to 0.5, there are intervals after \(\tau =0\) and before \(\tau =1\) during which the spacecraft angular velocity, angular acceleration, and control torque are all approximately equal to zero leading to higher maneuvering times. A good compromise is given by \(W=0.015\).

Fig. 1
figure 1

Samples of basis functions \(v_k(\tau _{\ell }) \ \ k=1,\ldots ,4 \ \ \ell =1,\ldots ,500\)

The time behaviors of the Slepian sequences corresponding to the selected values are reported in Fig. 1 and show that \(v_k(0) \simeq 0, \dfrac{d v_k}{d \tau }(0) \simeq 0, v_k(1) \simeq 0, \dfrac{d v_k}{d \tau }(1) \simeq 0\). As a result, by Eq. (3), the following holds \( \varvec{\omega ^*}(0) \simeq \mathbf {0}, \ \ \ \dfrac{d \varvec{\omega ^*}}{d \tau }(0) \simeq \mathbf {0}, \ \ \ \varvec{\omega ^*}(1) \simeq \mathbf {0}, \ \ \ \dfrac{d \varvec{\omega ^*}}{d \tau }(1) \simeq \mathbf {0} \) ensuring that a rest-to-rest maneuver is obtained and that the resulting control torque \(\mathbf {T}(t)\) will vanish at \(t=0\) and \(t=t_f\). Since only \(v_k(\tau _{\ell })\) are known, then for fixed \(\alpha _{jk}\) only the values \(\varvec{\omega ^*}(\tau _{\ell })\) are determined [see Eq (3)]. Thus, to integrate Eq. (4), the continuous-time behavior \(\varvec{\omega ^*}(\tau ) \ 0 \le \tau \le 1\) is obtained from \(\varvec{\omega ^*}(\tau _{\ell })\) using the zero-order hold interpolation. Moreover, samples \(\mathbf {T}^*(\tau _{\ell })\) are determined through Eq. (8) employing a finite difference approximation for computing \(\dfrac{d \varvec{\omega }^*}{d \tau }(\tau )\).

Table 1 Comparison of the proposed derivative-free approach with the gradient-based approach used in [9] in the solution of Case 1

The values of the weights \(\alpha _{jk}\) for \( j=1,2,3, \ k=1,2,3,4\), minimizing \(t_f\) are obtained by solving the described optimization problem CP corresponding to this case. As explained, it is not possible to provide the analytic expression of CP. However, given numerical values for the \(\alpha _{jk}\), we use a MATLAB simulation to compute the selected objective function, the equality and the inequality constraints. This simulation is called within the derivative-free algorithm to evaluate each point tested by the algorithm. The algorithm itself is implemented in MATLAB and proceeds by alternating phases of Minimization of the Maneuvering Time (MMT) and phases of Minimization of the Sum of the Squared Alphas (MSSA). To compute the solution reported in Table 1, the algorithm uses 5 phases: the first pursuing MMT, the second pursuing MSSA , and so on, until the last one pursuing MMT. For the first 4 phases, 10,000 iterations per phase were enough to numerically reach a local minimum, while the last phase required 30,000 iterations. If the iterations are protracted beyond such values, there are no numerically appreciable improvements. The total computing time to obtain this solution was 136 min on a PC with i9 processor and 128 Gb of RAM. The obtained maneuvering time is \(t_f= 755\) sec. The corresponding control torque is reported in Fig. 2, showing that from a practical point of view it is continuously differentiable and vanishes at its endpoints. To validate the effectiveness of the obtained control torque, the attitude kinematics and dynamics with the appropriate initial conditions \(\mathbf {R}(0)=\mathbf {I}_{3 \times 3} \ \ \varvec{\omega }(0)=0\) are integrated numerically using a method that preserves orthonormality of \(\mathbf {R}\), and the following results are obtained. The obtained final attitude \(\mathbf {R}(t_f)\) satisfies \( 3- \mathrm {tr} \left[ \mathbf {R_f}^T \mathbf {R}(t_f) \right] =9.21 \ 10^{-5} \) and \(\Vert \varvec{\omega }(t_f) \Vert = 4.58 \ 10^{-6}\). The time behaviors of \( c_i(t)=\mathbf {r}^T \mathbf {R}(t)^T \mathbf {w}_i - \cos \theta _{i} \ \ \ i=1,2 \) are shown in Fig. 3 confirming that the two pointing constraints are fulfilled. The path of the sensitive direction is displayed in Fig. 4.

Fig. 2
figure 2

Case study 1—Control torque obtained using the proposed method

Fig. 3
figure 3

Case study 1—Pointing constraints obtained using the proposed method

Fig. 4
figure 4

Case study 1—Path of sensitive direction (black curve) obtained using the proposed method, exclusion cones, initial sensitive direction (green arrow), desired final sensitive direction (blue arrow)

This case study has been also solved for comparison with the method proposed in [9]. That method also uses the expansion in Eq. (3) to obtain a control torque that is continuously differentiable and vanishes at its endpoints. However, it differs in the following aspects: (1) the weights are selected only as those that minimize the sum of the squared alphas (in other words, pursuing only the approximate objective MSSA); (2) approximate expressions for the constraints are used. Both aspects are needed to be able to compute the gradient of cost function and constraints, and therefore solve this approximate CP using a gradient-based method, in particular the interior point method described in [7]. Slepian sequences have been selected again as basis functions, and many tests have been performed with different values for M, N, W and for the configuration parameters of the gradient-based interior point method. The lowest maneuvering time is achieved with \(N=500\), \(M=4\), \(W=0.015\) and it is equal to \(t_f=2.73\ 10^3\) sec. The corresponding path of the sensitive direction is reported in Fig. 5. Clearly, the solution obtained with the approach proposed in this work is superior and much more useful from a practical point of view.

Fig. 5
figure 5

Case study 1—Path of sensitive direction (black curve) obtained using the method in [9], exclusion cones, initial sensitive direction (green arrow), desired final sensitive direction (blue arrow)

The maneuvering time achieved in [29] is \(t_f=405\) sec, which is significantly shorter than \(t_f=755\) sec obtained with the approach proposed here. However, the method in [29] does not guarantee that the corresponding control torque, which is not displayed in that work, is continuously differentiable and vanishes at its endpoints. Thus, it is very likely that its implementation will require a faster, and consequently costly, torque actuator.

4.2 Case Study 2

The second case study has been formulated in [25] and again in [21], and it is inspired by the following maneuver performed by the Swift spacecraft. The satellite must perform a fast reorientation maneuver to point two telescopes at a desired gamma-ray burst. The spacecraft is equipped with a Burst Alert Telescope that first senses the gamma-ray burst, and the satellite then must perform a slew to allow the x-ray and UV/optical instruments to capture the afterglow of the event which quickly fades. To prevent damage to the telescopes, their common axis must not enter three keep-out cones with central axes pointing to the sun, the Earth, and the moon and appropriate offset angles. As an example, assume that the spacecraft has to perform a rotation of 135 deg about its z-axis. Thus, setting the initial attitude as \(\mathbf {R_i }=\mathbf {I}_{3 \times 3}\), the desired final attitude is equal to \(\mathbf {R_f}=\exp (3/4 \pi \mathbf {A_3})\). The telescopes axis has coordinates \(\mathbf {r}=[1 \ 0 \ 0 ]^T\) in body frame. The three keep-out cones are specified ad follows: (1) sun cone with inertial direction \(\mathbf {w}_1=[0.5 \ 0.866 \ 0]^T\) and minimum offset angle \(\theta _1=47\) deg; (2) Earth cone with inertial direction \(\mathbf {w}_2=[0 \ 0 \ -1]^T\) and minimum offset angle \(\theta _2=33\) deg; 3) moon cone with inertial direction \(\mathbf {w}_3=[0.1795 \ 0.3109 \ 0.9333]^T\) and minimum offset angle \(\theta _3=23\) deg. There is a gap of 10 deg between the sun and Earth cones but no gap between the sun and moon cones (see Fig. 6).

Fig. 6
figure 6

Case study 2—Path of sensitive direction (black curve) obtained using the proposed method, exclusion cones, initial sensitive direction (green arrow), desired final sensitive direction (blue arrow)

The basis functions have been selected following the same guidelines used in case study 1. Specifically they are defined only at the discrete times \(\tau _{\ell } \ \ell =1,\ldots ,N\) and have been chosen as the first \(M=4\) Slepian sequences with \(N=500\) and \(W=0.015\) [28] (see Fig. 1). Consider an isoinertial spacecraft so that \(\mathbf {J}=J_0 \mathbf {I}_{3 \times 3}\) and introduce time unit \(\mathrm {TU}=\sqrt{J_0/\bar{T}}\). It is immediate to see that the maneuvering time in Eq. (10) can be expressed as follows \(t_f=\mathrm {TU} \sqrt{\overline{T^*}/J_0}\) where \(\overline{T^*}\) was defined in Eq. (9) Thus, for fixed weights \(\alpha _{jk}\), the maneuvering time expressed in TU units can be computed using the previous expression.

Again, the values of the weights \(\alpha _{jk}\) for \( j=1,2,3, \ k=1,2,3,4\) minimizing \(t_f\) are obtained by solving the optimization problem CP corresponding to this case. To compute the solution reported in Table 2, the algorithm uses 3 phases: the first pursuing MMT, the second pursuing MSSA, the last one pursuing MMT. The number of iterations per phase was 10,000, and this was large enough to numerically reach a local minimum. The total computing time to obtain this solution was 55 min on a PC with i9 processor and 128 Gb of RAM. The obtained maneuvering time is \(t_f= 5.90\) TU. The corresponding control torque is reported in Fig. 7, showing that from a practical point of view it is continuously differentiable and vanishes at its endpoints. To validate the effectiveness of the obtained control torque, the attitude kinematics and dynamics with the appropriate initial conditions \(\mathbf {R}(0)=\mathbf {I}_{3 \times 3} \ \ \varvec{\omega }(0)=0\) are integrated numerically using a method that preserves orthonormality of \(\mathbf {R}\), and the following results are obtained. The obtained final attitude \(\mathbf {R}(t_f)\) satisfies \( 3- \mathrm {tr} \left[ \mathbf {R_f}^T \mathbf {R}(t_f) \right] =4.59 \ 10^{-5} \) and \(\Vert \varvec{\omega }(t_f) \Vert = 6.82 \ 10^{-7}\). The time behaviors of \( c_i(t)=\mathbf {r}^T \mathbf {R}(t)^T \mathbf {w}_i - \cos \theta _{i} \ \ \ i=1,2,3 \) are shown in Fig. 8 confirming that the three pointing constraints are fulfilled. The path of the sensitive direction is displayed in Fig. 6.

Table 2 Comparison of the proposed derivative-free approach with the gradient-based approach used in [9] in the solution of Case 2
Fig. 7
figure 7

Case study 2—Control torque obtained using the proposed method

Fig. 8
figure 8

Case study 2—Pointing constraints obtained using the proposed method

We compare our solution to those reported in [9] and [21] for the same case study. The solution in [9] is obtained by expressing the angular velocity as weighted sum of the same Slepian functions. Hence, the obtained control torque is continuously differentiable and vanishes at its endpoints (figure 3 of [9]). The weights, computed in that case by means of a gradient-descent optimization, are not explicitly reported in [9] but are known to the first author and are reported in Table 2. The resulting maneuvering time is \(t_f=6.26\) TU, which is longer compared to the \(t_f=5.90\) TU achieved here, and the obtained control torque leads to a less accurate fulfillment of the pointing constraints (compare figure 5 of [9] with Fig. 8).

The solution in [21] is obtained by using a completely different approach in which the angular velocity is not constrained to be the a linear combination of fixed basis functions. The control torque obtained in that work leads to a maneuvering time \(t_f\) of about 3.5 TU, which is significantly shorter than the value \(t_f=5.90\) TU obtained here. However, the control torque in [21] does not vanish at its endpoints, and it has a very steep behavior in some parts (see figure 26 of [21]). As a result, compared to the control torque obtained here (see Fig. 7), it requires much faster, and consequently costly, torque actuators to be implemented on a real spacecraft.

5 Conclusions

The spacecraft attitude motion planning approach presented in this work provides a systematic method for performing minimum-time rest-to-rest maneuvers taking into account multiple pointing constraints and with the additional requirement of obtaining control torques that are continuously differentiable and vanish at their endpoints. The latter requirement is important from a practical point of view, since that type of control torques are simpler to implement than those determined through other methods which do not guarantee such properties. Our approach requires the solution of a difficult constrained optimization problem which is pursued by using a derivative-free solution strategy with the alternation of two objective functions. In the analysis of two case studies taken from the literature, the proposed approach leads to solutions which are better than those obtained with a similar existing method relying on gradient-based optimization.