Module: thrForceMapping

Executive Summary

This module is reads in a desired attitude control torque vector and maps it onto a set of thrusters.

The module works for both on-pulsing (nominal thruster state is off such as with RCS thrusters) and off-pulsing (nominal thruster state in such as with DV thrusters). More information can be found in the PDF Description.

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

thrForceCmdOutMsg

THRArrayCmdForceMsgPayload

thruster force output message

cmdTorqueInMsg

CmdTorqueBodyMsgPayload

commanded attitude control torque vector input message

thrConfigInMsg

THRArrayConfigMsgPayload

Thruster array configuration input message

vehConfigInMsg

VehicleConfigMsgPayload

spacecraft configuration input message


Functions

void SelfInit_thrForceMapping(thrForceMappingConfig *configData, int64_t moduleID)

self init method

Parameters:
  • configData – The configuration data associated with this module

  • moduleID – The ID associated with the configData

Returns:

void

void Update_thrForceMapping(thrForceMappingConfig *configData, uint64_t callTime, int64_t moduleID)

The module takes a body frame torque vector and projects it onto available RCS or DV thrusters.

Parameters:
  • configData – The configuration data associated with the module

  • callTime – The clock time at which the function was called (nanoseconds)

  • moduleID – The ID associated with the configData

Returns:

void

void Reset_thrForceMapping(thrForceMappingConfig *configData, uint64_t callTime, int64_t moduleID)

This method performs a complete reset of the module. Local module variables that retain time varying states between function calls are reset to their default values.

Parameters:
  • configData – The configuration data associated with the module

  • callTime – The clock time at which the function was called (nanoseconds)

  • moduleID – The ID associated with the configData

Returns:

void

void substractMin(double *F, uint32_t size)

Take a stack of force values find the smallest value, and subtract if from all force values. Here the smallest values will become zero, while other forces increase. This assumes that the thrusters are aligned such that if all thrusters are firing, then no torque or force is applied. This ensures only positive force values are computed.

void findMinimumNormForce(thrForceMappingConfig *configData, double D[3][MAX_EFF_CNT], double Lr_B[3], uint32_t numForces, double F[MAX_EFF_CNT])

Use a least square inverse to determine the smallest set of thruster forces that yield the desired torque vector. Note that this routine does not constrain yet the forces to be either positive or negative

double computeTorqueAngErr(double D[3][MAX_EFF_CNT], double BLr[3], uint32_t numForces, double epsilon, double F[MAX_EFF_CNT], double FMag[MAX_EFF_CNT])

Determine the angle between the desired torque vector and the actual torque vector.

struct thrForceMappingConfig
#include <thrForceMapping.h>

Data structure for module to map a command torque onto thruster forces.

Public Members

double controlAxes_B[3 * 3]

[] array of the control unit axes

double rThruster_B[MAX_EFF_CNT][3]

[m] local copy of the thruster locations

double gtThruster_B[MAX_EFF_CNT][3]

[] local copy of the thruster force unit direction vectors

int32_t thrForceSign

[] Flag indicating if pos (+1) or negative (-1) thruster solutions are found

double angErrThresh

[r] Angular error at which thruster forces are scaled to not be super-saturated

double epsilon

variable specifying what is considered a small number

uint32_t use2ndLoop

[] flag indicating if the 2nd least squares fitting loop should be used (1) or not used (0 - default)

uint32_t numControlAxes

[] counter indicating how many orthogonal axes are controlled

uint32_t numThrusters

[] The number of thrusters available on vehicle

double outTorqAngErr

[r] Angular error of effector torque

double thrForcMag[MAX_EFF_CNT]

vector of thruster force magnitudes

THRArrayCmdForceMsg_C thrForceCmdOutMsg

The name of the output thruster force message.

CmdTorqueBodyMsg_C cmdTorqueInMsg

The name of the vehicle control (Lr) Input message.

THRArrayConfigMsg_C thrConfigInMsg

The name of the thruster cluster Input message.

VehicleConfigMsg_C vehConfigInMsg

The name of the Input message.

VehicleConfigMsgPayload sc

spacecraft configuration message

BSKLogger *bskLogger

BSK Logging.