Module: constrainedAttitudeManeuver

Executive Summary

Module to maneuver a spacecraft subject to hard rotational constraints. This module enables the user to add keep-in and keep-out zones that must not be violated by certain user-specified body-frame directions during the maneuver. See the Detailed Module Description for a better description on how this is achieved. The module produces an Attitude Reference Message containing the reference trajectory that is tracked by the spacecraft.

Message Connection Descriptions

The following table lists all the module input and output messages. The module msg connection is set by the user from python. The msg type contains a link to the message structure definition, while the description provides information on what this message is used for.

Module I/O Messages

Msg Variable Name

Msg Type

Description

attRefOutMsg

AttRefMsgPayload

Output Attitude Reference Message.

attRefOutMsgC

AttRefMsgPayload

C-wrapped Output Attitude Reference Message.

scStateInMsg

SCStatesMsgPayload

Input SC States Message.

vehicleConfigInMsg

VehicleConfigMsgPayload

Input Vehicle Configuration Message.

keepOutCelBodyInMsg

SpicePlanetStateMsgPayload

Input keep-out Planet State Message.

keepInCelBodyInMsg

SpicePlanetStateMsgPayload

Input keep-in Planet State Message.

Module Assumptions and Limitations

The module, in its current form, allows to only include one keep-out and one keep-in celestial object(s). Multiple boresights (up to 10) can be specified as either keep-in or keep-out body directions. The keep-out constraint is considered respected when all the keep-out body-fixed boresights are outside of the keep-out zone simultaneously. On the contrary, the keep-in constraint is considered respected when at least one keep-in body-fixed direction is inside the keep-in zone.

At this stage of development, constraint compliance is only guaranteed for the attitude waypoints that are used as a base for the interpolation that yields the attitude reference trajectory (see Detailed Module Description below). It may happen that portions of the reference trajectory between waypoints still violate the rotational constraints. Ensuring that this does not happen will be subject of further refinements of this module. For the time being, it is possible to circumvent this problem changing the grid refinement level N. This changes the coordinates of the grid points, thus yielding a different reference trajectory for every N. A small N results in a coarser grid, which is more likely to yield a trajectory that violates some constraints, but is generally smoother. Viceversa, a higher N gives a finer grid where the chance of obtaining a constraint-incompliant grid is reduced. However, the trajectory in this case is less regular due to the fact that the interpolating curve is forced to pass through a larger number of waypoints. A higher N is also associated with a higher computational cost.

Detailed Module Description

A detailed explanation of the method implemented in this module can be found in R. Calaon and H. Schaub, “Constrained Attitude Maneuvering via Modified-Rodrigues-Parameter-Based Motion Planning Algorithms”. To summarize, this module builds a 3D grid in MRP space, whose density is regulated by the input parameter N. Each grid node corresponds to an attitude. An undirected graph is built with all the nodes that are constraint compliant. Two nodes are added to the graph:

  • startNode whose coordinates \(\sigma_{BN,S}\) correspond to the attitude of the spacecraft contained in the vehicleConfigInMsg;

  • goalNode whose coordinates \(\sigma_{BN,G}\) correspond to the desired target attitude at the end of the maneuver.

Two different cost functions are used by the \(A^*\) algorithm to search a valid path. The first is based on the total cartesian length of the path in MRP space. The second is the effort-based cost function computed integrating the control torque norm over the interpolated trajectory obtained from a path., as explained in R. Calaon and H. Schaub. In both cases, the final reference passed to the Attitude Reference Message consists in the interpolated curve obtained from the optimal path computed by \(A^*\), based on the chosen cost function. Interpolation is performed using the routine in BSpline.

Note that this module does not implement the constant angular rate norm routine described in R. Calaon and H. Schaub. The attitude, rates and accelerations provided to the Attitude Reference Message are those obtained directly from the BSpline interpolation.

User Guide

The required module configuration is:

CAM = constrainedAttitudeManeuver.ConstrainedAttitudeManeuver(N)
CAM.ModelTag = "constrainedAttitudeManeuvering"
CAM.sigma_BN_goal = sigma_BN_G
CAM.omega_BN_B_goal = [0, 0, 0]
CAM.avgOmega = 0.04
CAM.BSplineType = 0
CAM.costFcnType = 0
CAM.appendKeepOutDirection([1,0,0], keepOutFov)
CAM.appendKeepInDirection([0,1,0], keepInFov)
scSim.AddModelToTask(simTaskName, CAM)

The module is configurable with the following parameters:

Module Parameters

Parameter

Description

sigma_BN_goal

goal MRP attitude set

omega_BN_B_goal

desired angular rate at goal, in body frame coordinates

avgOmega

average angular rate norm desired for the maneuver

BSplineType

desired type of BSpline: 0 for precise interpolation, 1 for least-squares approximation

costFcnType

desired cost function for the graph search algorithm: 0 for total MRP distance, 1 for effort-based cost.


Functions

void mirrorFunction(int indices[3], int mirrorIndices[8][3])

This helper function returns the coordinates of the 8 symmetrical points to a point in 3D cartesian space.

void neighboringNodes(int indices[3], int neighbors[26][3])

For a set of indices, this helper function returns the indices of the 26 immediate neighbors.

double distance(Node n1, Node n2)

This function implements the MRP cartesian distance between 2 nodes.

struct constraintStruct
#include <constrainedAttitudeManeuver.h>

The constraintStruc structure is used to store the inertial direction of the keep-in and keep-out zones.

Public Members

double keepOutDir_N[3]

Inertial direction of keepOut celestial bodies.

double keepInDir_N[3]

Inertial direction of keepIn celestial bodies.

bool keepOut

Flag to assess whether keepOut constraints are being considered.

bool keepIn

Flag to assess whether keepIn constraints are being considered.

struct scBoresightStruct
#include <constrainedAttitudeManeuver.h>

The scBoresightStruc structure is used to store the body frame directions and fields of view of the instruments.

Public Members

double keepOutBoresight_B[10][3]

Unit vectors containing body frame directions of keepOut instruments.

double keepInBoresight_B[10][3]

Unit vectors containing body frame directions of keepIn instruments.

double keepOutFov[10]

Fields of view of the keepOut instruments.

double keepInFov[10]

Fields of view of the keepIn instruments.

int keepOutBoresightCount = 0

Number of keepOut sensitive instruments.

int keepInBoresightCount = 0

Number of keepIn instruments.

class Node
#include <constrainedAttitudeManeuver.h>

The Node class is used to create nodes in the 3D MRP graph.

Public Functions

Node()

This is the constructor for the Node class. It sets default variable values and initializes the various parts of the model

Node(double sigma_BN[3], constraintStruct constraints, scBoresightStruct boresights)

The constructor requires the MRP set, the constraint structure and the sc boresight structure

~Node()

Module Destructor.

void appendNeighbor(Node *node)

This method appends a pointer to neighboring node to the neighbors class variable

Public Members

double sigma_BN[3]

MRP set corresponding to the node.

bool isBoundary

If true, the node lies on the |sigma| = 1 boundary surface.

bool isFree

If true, the node is constraint-compliant.

double heuristic

Heuristic value used by cartesian distance A*.

double priority

Priority of the node in A*.

Node *neighbors[52]

Container of pointers to neighboring nodes.

int neighborCount

Number of neighboring nodes.

Node *backPointer

Pointer to the previous node in the path computer by A*.

class NodeList
#include <constrainedAttitudeManeuver.h>

The NodeList class is used in the A* algorithm to handle Open and Closed lists O and C.

Public Functions

NodeList()

This is the constructor for the NodeList class.

~NodeList()

Class Destructor.

void append(Node *node)

This method appends a pointer to the node list.

void pop(int M)

This method removes the pointer at index M from the node list.

void clear()

This method resets the list counter to 0, effectively clearing the list.

void swap(int m, int n)

This method swaps the two pointers at indices m and n.

void sort()

This method sorts the nodes in the list according to their priority.

bool contains(Node *node)

This method returns true if a node is contained in the list, false otherwise.

Public Members

Node *list[10000]

Container of pointers to the nodes in the list.

int N

Number of nodes in the list.

class ConstrainedAttitudeManeuver : public SysModel
#include <constrainedAttitudeManeuver.h>

waypoint reference module class

Public Functions

ConstrainedAttitudeManeuver()

This is the constructor for the module class. It sets default variable values and initializes the various parts of the model

ConstrainedAttitudeManeuver(int N)

This is the constructor for the module class. It sets default variable values and initializes the various parts of the model

~ConstrainedAttitudeManeuver()

Module Destructor.

void SelfInit()

Self initialization for C-wrapped messages.

Initialize C-wrapped output messages

void Reset(uint64_t CurrentSimNanos)

This method is used to reset the module. The input messages are read here, the grid is generated and the graph search is performed.

void UpdateState(uint64_t CurrentSimNanos)

This method is the state update. It reads the information from the interpolated trajectory and writes the output message.

Parameters

CurrentSimNanos – The current simulation time for system

Returns

void

void ReadInputs()

This method reads the input messages in from the system and sets the appropriate parameters

Returns

void

void GenerateGrid(Node startNode, Node goalNode)

This method generates the MRP grid and connects the free neighboring nodes

Returns

void

void appendKeepOutDirection(double direction[3], double Fov)

Add keep-out body-frame direction

void appendKeepInDirection(double direction[3], double Fov)

Add keep-in body-frame direction

void AStar()

This method applies standard distance-based A* to find a valid path

Returns

void

void effortBasedAStar()

This method applies the effort-based A* to find a valid path

Returns

void

void backtrack(Node *p)

This method is used inside A* to track the path from goal to start, order it from start to goal and store in class variable path

Returns

void

void pathHandle()

This method takes a path of waypoints and returns an Input structure suitable for BSpline interpolation/approximation

Returns

void

void spline()

This method performs the BSpline interpolation/approximation and outputs an Output structure

Returns

void

void computeTorque(int n, double I[9], double L[3])

This method computes the torque vector required at time step with index n

Returns

void

double computeTorqueNorm(int n, double I[9])

This method computes the torque vector required at time step with index n

Returns

void

double effortEvaluation()

This method integrates the control torque norm over maneuver time and returns the cost for the effort-based A*.

Returns

void

double returnNodeCoord(int key[3], int nodeCoord)

This method allows to access the coordinates of a Node in NodesMap without swigging the C++ Map. It is designed to be used in the UnitTest primarily.

Returns

void

bool returnNodeState(int key[3])

This method allows to access the state of a Node (free or not free) in NodesMap without swigging the C++ Map. It is designed to be used in the UnitTest primarily.

Returns

void

double returnPathCoord(int index, int nodeCoord)

This method allows to access the coordinates of path Nodes in without swigging NodesList C++. It is designed to be used in the UnitTest primarily.

Returns

void

Public Members

int N

Fineness level of discretization.

int BSplineType

0 for interpolation; 1 for LS approximation

int costFcnType

0 for minimum distance path; 1 for minimum control effort path

double sigma_BN_goal[3]

Initial S/C attitude.

double omega_BN_B_goal[3]

Initial S/C angular rate.

double avgOmega

Average angular rate norm during the maneuver.

double keepOutFov

Field of view of the sensitive instrument.

double keepOutBore_B[3]

Body-frame direction of the boresight of the sensitive instrument.

constraintStruct constraints

Structure containing the constraint directions in inertial coordinates.

scBoresightStruct boresights

Structure containing the instrument boresight directions in body frame coordinates.

std::map<int, std::map<int, std::map<int, Node>>> NodesMap

C++ map from node indices to Node class.

int keyS[3]

Key to Start node in NodesMap.

int keyG[3]

Key to Goal node in NodesMap.

NodeList path

Path of nodes from start to goal.

double pathCost

Cost of the path above, according to the cost function used.

InputDataSet Input

Input structure for the BSpline interpolation/approximation.

OutputDataSet Output

Output structure of the BSpline interpolation/approximation.

ReadFunctor<SCStatesMsgPayload> scStateInMsg

Spacecraft state input message.

ReadFunctor<VehicleConfigMsgPayload> vehicleConfigInMsg

FSW vehicle configuration input message.

ReadFunctor<SpicePlanetStateMsgPayload> keepOutCelBodyInMsg

Celestial body state msg - keep out direction.

ReadFunctor<SpicePlanetStateMsgPayload> keepInCelBodyInMsg

Celestial body state msg - keep in direction.

Message<AttRefMsgPayload> attRefOutMsg

Attitude reference output message.

AttRefMsg_C attRefOutMsgC = {}

C-wrapped attitude reference output message.

BSKLogger bskLogger

BSK Logging.

Private Members

SCStatesMsgPayload scStateMsgBuffer
VehicleConfigMsgPayload vehicleConfigMsgBuffer
SpicePlanetStateMsgPayload keepOutCelBodyMsgBuffer
SpicePlanetStateMsgPayload keepInCelBodyMsgBuffer