Module: spinningBodyNDOFStateEffector
Executive Summary
The N-degree-of-freedom spinning body class is an instantiation of the state effector abstract class. The integrated test is validating the interaction between the N-DoF spinning body module and the rigid body hub that it is attached to. In this case, an N-DoF spinning body system has four masses and four inertia tensors. The lower axis is attached to the hub and the upper axis is attached to the lower body. This module can represent multiple different effectors, with any number of degrees of freedom. A spring and damper can be included in each axis, and an optional motor torque can be applied on each spinning axis.
Nominally, each degree of freedom corresponds to an additional rigid body link. However, by setting the mass and the inertia of to 0, the module can simulate multiple degrees of freedom for the same spinning body instead.
Message Connection Descriptions
The following table lists all the module input and output messages. The module msg variable name 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.
Msg Variable Name |
Msg Type |
Description |
---|---|---|
spinningBodyOutMsgs |
Output vector of messages containing the spinning body state angle and angle rate |
|
motorTorqueInMsg |
(Optional) Input message of the motor torque value |
|
motorLockInMsg |
(Optional) Input message for locking the axis |
|
spinningBodyConfigLogOutMsgs |
Output vector of messages containing the spinning body inertial position and attitude states |
Detailed Module Description
An N-DoF spinning body has 2N states: theta
, thetaDot
for each degree of freedom.
Mathematical Modeling
See the following conference paper for a detailed description of this model.
Note
J. Vaz Carneiro, C. Allard and H. Schaub, “Effector Dynamics For Sequentially Rotating Rigid Body Spacecraft Components”, AAS Astrodynamics Specialist Conference, Bog Sky, MT, Aug. 13-17, 2023
User Guide
This section is to outline the steps needed to setup a Spinning Body N DoF State Effector in Python using Basilisk.
Import the spinningBodyNDOFStateEffector class:
from Basilisk.simulation import spinningBodyNDOFStateEffector
Create an instantiation of a Spinning body:
spinningBodyEffector = spinningBodyNDOFStateEffector.SpinningBodyNDOFStateEffector()
Define all physical parameters for each spinning body. For example:
spinningBody = spinningBodyNDOFStateEffector.SpinningBody() spinningBody.setMass(25.0) spinningBody.setISPntSc_S([[50, 0.0, 0.0], [0.0, 40, 0.0], [0.0, 0.0, 30]]) spinningBody.setDCM_S0P([[-1.0, 0.0, 0.0], [0.0, -1.0, 0.0], [0.0, 0.0, 1.0]]) spinningBody.setR_ScS_S([[0.2], [-0.3], [0.1]]) spinningBody.setR_SP_P([[-0.05], [0.0], [0.1]]) spinningBody.setSHat_S([[0], [0], [1]]) spinningBodyEffector.addSpinningBody(spinningBody)
(Optional) Define initial conditions of the effector. Default values are zero states:
spinningBody.setThetaInit(10.0 * macros.D2R) spinningBody.setThetaDotInit(-1.0 * macros.D2R)
(Optional) Define spring and damper coefficients. Default values are zero states:
spinningBody.setK(100) spinningBody.setC(20)
(Optional) Define a unique name for each state. If you have multiple spinning bodies, they each must have a unique name. If these names are not specified, then the default names are used which are incremented by the effector number:
spinningBodyEffector.setNameOfThetaState = "spinningBodyTheta" spinningBodyEffector.setNameOfThetaDotState = "spinningBodyThetaDot"
(Optional) Connect a command torque message:
cmdArray = messaging.ArrayMotorTorqueMsgPayload() cmdArray.motorTorque = [cmdTorque] # [Nm] cmdMsg = messaging.ArrayMotorTorqueMsg().write(cmdArray) spinningBody.motorTorqueInMsg.subscribeTo(cmdMsg)
(Optional) Connect an axis-locking message (0 means the axis is free to rotate and 1 locks the axis):
lockArray = messaging.ArrayEffectorLockMsgPayload() lockArray.motorTorque = [1] lockMsg = messaging.ArrayEffectorLockMsg().write(lockArray) spinningBody.motorLockInMsg.subscribeTo(lockMsg)
The angular states of the body are created using an output vector of messages
spinningBodyOutMsgs
.The spinning body config log state output messages is
spinningBodyConfigLogOutMsgs
.Add the effector to your spacecraft:
scObject.addStateEffector(spinningBody)
See Module: spacecraft documentation on how to set up a spacecraft object.
Add the module to the task list:
unitTestSim.AddModelToTask(unitTaskName, spinningBody)
-
struct SpinningBody
- #include <spinningBodyNDOFStateEffector.h>
Struct containing all the spinning bodies variables.
Public Functions
-
void setMass(double mass)
setter for
mass
property
-
inline void setR_SP_P(Eigen::Vector3d r_SP_P)
setter for
r_SP_P
property
-
inline void setR_ScS_S(Eigen::Vector3d r_ScS_S)
setter for
r_ScS_S
property
-
inline void setISPntSc_S(const Eigen::Matrix3d &ISPntSc_S)
setter for
ISPntSc_S
property
-
void setSHat_S(Eigen::Vector3d sHat_S)
setter for
sHat_S
property
-
inline void setDCM_S0P(const Eigen::Matrix3d &dcm_S0P)
setter for
dcm_S0P
property
-
void setK(double k)
setter for
k
property
-
void setC(double c)
setter for
c
property
-
inline void setThetaInit(double thetaInit)
setter for
thetaInit
property
-
inline void setThetaDotInit(double thetaDotInit)
setter for
thetaDotInit
property
-
inline double getMass() const
getter for
mass
property
-
inline Eigen::Vector3d getR_SP_P() const
getter for
r_SP_P
property
-
inline Eigen::Vector3d getR_ScS_S() const
getter for
r_ScS_S
property
-
inline Eigen::Matrix3d setISPntSc_S() const
getter for
ISPntSc_S
property
-
inline Eigen::Vector3d getSHat_S() const
getter for
sHat_S
property
-
inline Eigen::Matrix3d getDCM_S0P() const
getter for
dcm_S0P
property
-
inline double getK() const
getter for
k
property
-
inline double getC() const
getter for
c
property
-
inline double getThetaInit() const
getter for
thetaInit
property
-
inline double getThetaDotInit() const
getter for
thetaDotInit
property
Private Members
-
double thetaInit = 0.0
[rad] initial spinning body angle
-
double thetaDotInit = 0.0
[rad/s] initial spinning body angle rate
-
double k = 0.0
[N-m/rad] torsional spring constant
-
double c = 0.0
[N-m-s/rad] rotational damping coefficient
-
double mass = 1.0
[kg] spinning body mass
-
Eigen::Vector3d r_SP_P = Eigen::Vector3d::Zero()
[m] vector pointing from parent frame P origin to spinning frame S origin in P frame components
-
Eigen::Vector3d r_ScS_S = Eigen::Vector3d::Zero()
[m] vector pointing from spinning frame S origin to point Sc (center of mass of the spinner) in S frame components
-
Eigen::Vector3d sHat_S = {1.0, 0.0, 0.0}
spinning axis in S frame components
-
Eigen::Matrix3d dcm_S0P = Eigen::Matrix3d::Identity()
DCM from the parent frame to the S0 frame (S frame for theta=0)
-
Eigen::Matrix3d ISPntSc_S = Eigen::Matrix3d::Identity()
[kg-m^2] Inertia of spinning body about point Sc in S frame components
-
double theta = 0.0
[rad] current spinning body angle
-
double thetaDot = 0.0
[rad/s] current spinning body angle rate
-
double thetaRef = 0.0
[rad] reference spinning body angle
-
double thetaDotRef = 0.0
[rad/s] reference spinning body angle rate
-
double u = 0.0
[N-m] initial spinning body angle
-
bool isAxisLocked = false
axis lock flag
-
Eigen::Vector3d sHat_B = {1.0, 0.0, 0.0}
spinning axis in B frame components
-
Eigen::Vector3d r_SP_B = Eigen::Vector3d::Zero()
[m] vector pointing from parent frame P origin to spinning frame S origin in B frame components
-
Eigen::Vector3d r_SB_B = Eigen::Vector3d::Zero()
[m] vector pointing from body frame B origin to spinning frame S origin in B frame components
-
Eigen::Vector3d r_ScS_B = Eigen::Vector3d::Zero()
[m] vector pointing from spinning frame S origin to point Sc (center of mass of the spinner) in B frame components
-
Eigen::Vector3d r_ScB_B = Eigen::Vector3d::Zero()
[m] vector pointing from body frame B origin to point Sc (center of mass of the spinner) in B frame components
-
Eigen::Vector3d rPrime_SP_B = Eigen::Vector3d::Zero()
[m/s] body frame time derivative of r_SP_B in B frame components
-
Eigen::Vector3d rPrime_SB_B = Eigen::Vector3d::Zero()
[m/s] body frame time derivative of r_SB_B in B frame components
-
Eigen::Vector3d rPrime_ScS_B = Eigen::Vector3d::Zero()
[m/s] body frame time derivative of r_ScS_B in B frame components
-
Eigen::Vector3d rPrime_ScB_B = Eigen::Vector3d::Zero()
[m/s] body frame time derivative of r_ScB_B in B frame components
-
Eigen::Vector3d rDot_ScB_B = Eigen::Vector3d::Zero()
[m/s] inertial time derivative of r_ScB_B in B frame components
-
Eigen::Vector3d omega_SP_B = Eigen::Vector3d::Zero()
[rad/s] angular velocity of the S frame wrt the P frame in B frame components
-
Eigen::Vector3d omega_SB_B = Eigen::Vector3d::Zero()
[rad/s] angular velocity of the S frame wrt the B frame in B frame components
-
Eigen::Vector3d omega_SN_B = Eigen::Vector3d::Zero()
[rad/s] angular velocity of the S frame wrt the N frame in B frame components
-
Eigen::Matrix3d ISPntSc_B = Eigen::Matrix3d::Identity()
[kg-m^2] inertia of spinning body about point Sc in S frame components
-
Eigen::Matrix3d IPrimeSPntSc_B = Eigen::Matrix3d::Zero()
[kg-m^2] body frame derivative of the inertia of spinning body about point Sc in S frame components
-
Eigen::Matrix3d dcm_BS = Eigen::Matrix3d::Identity()
DCM from spinner frame to body frame.
-
Eigen::Matrix3d rTilde_ScB_B = Eigen::Matrix3d::Zero()
[m] tilde matrix of r_ScB_B
-
Eigen::Matrix3d omegaTilde_SP_B = Eigen::Matrix3d::Zero()
[rad/s] tilde matrix of omega_SP_B
-
Eigen::Matrix3d omegaTilde_SB_B = Eigen::Matrix3d::Zero()
[rad/s] tilde matrix of omega_SB_B
-
Eigen::Vector3d r_ScN_N = Eigen::Vector3d::Zero()
[m] position vector of the spinning body center of mass Sc relative to the inertial frame origin N
-
Eigen::Vector3d v_ScN_N = Eigen::Vector3d::Zero()
[m/s] inertial velocity vector of Sc relative to inertial frame
-
Eigen::Vector3d sigma_SN = Eigen::Vector3d::Zero()
MRP attitude of frame S relative to inertial frame.
-
Eigen::Vector3d omega_SN_S = Eigen::Vector3d::Zero()
[rad/s] inertial spinning body frame angular velocity vector
-
BSKLogger bskLogger
Friends
- friend class SpinningBodyNDOFStateEffector
-
void setMass(double mass)
-
class SpinningBodyNDOFStateEffector : public StateEffector, public SysModel
- #include <spinningBodyNDOFStateEffector.h>
spinning rigid body state effector class
Public Functions
-
SpinningBodyNDOFStateEffector()
Constructor.
-
~SpinningBodyNDOFStateEffector() override
Destructor.
-
void addSpinningBody(SpinningBody const &newBody)
method for adding a new spinning body
-
inline void setNameOfThetaState(const std::string &nameOfThetaState)
setter for
nameOfThetaState
property
-
inline void setNameOfThetaDotState(const std::string &nameOfThetaDotState)
setter for
nameOfThetaDotState
property
-
inline std::string getNameOfThetaState() const
getter for
nameOfThetaState
property
-
inline std::string getNameOfThetaDotState() const
getter for
nameOfThetaDotState
property
Public Members
-
std::vector<Message<HingedRigidBodyMsgPayload>*> spinningBodyOutMsgs
state output message
-
std::vector<Message<SCStatesMsgPayload>*> spinningBodyConfigLogOutMsgs
spinning body state config log message
-
ReadFunctor<ArrayMotorTorqueMsgPayload> motorTorqueInMsg
(optional) motor torque input message
-
ReadFunctor<ArrayEffectorLockMsgPayload> motorLockInMsg
(optional) lock flag input message
-
std::vector<ReadFunctor<HingedRigidBodyMsgPayload>> spinningBodyRefInMsgs
(optional) reference state input message
Private Functions
-
void Reset(uint64_t CurrentClock) override
-
void writeOutputStateMessages(uint64_t CurrentClock) override
-
void UpdateState(uint64_t CurrentSimNanos) override
-
void registerStates(DynParamManager &statesIn) override
-
void linkInStates(DynParamManager &states) override
-
void updateContributions(double integTime, BackSubMatrices &backSubContr, Eigen::Vector3d sigma_BN, Eigen::Vector3d omega_BN_B, Eigen::Vector3d g_N) override
-
void computeDerivatives(double integTime, Eigen::Vector3d rDDot_BN_N, Eigen::Vector3d omegaDot_BN_B, Eigen::Vector3d sigma_BN) override
-
void updateEffectorMassProps(double integTime) override
-
void updateEnergyMomContributions(double integTime, Eigen::Vector3d &rotAngMomPntCContr_B, double &rotEnergyContr, Eigen::Vector3d omega_BN_B) override
-
void prependSpacecraftNameToStates() override
-
void readInputMessages()
-
void computeSpinningBodyInertialStates()
-
void computeAttitudeProperties(SpinningBody &spinningBody, int spinningBodyIndex) const
-
void computeAngularVelocityProperties(SpinningBody &spinningBody, int spinningBodyIndex) const
-
void computePositionProperties(SpinningBody &spinningBody, int spinningBodyIndex) const
-
void computeVelocityProperties(SpinningBody &spinningBody, int spinningBodyIndex) const
-
void computeInertiaProperties(SpinningBody &spinningBody) const
-
void computeMTheta(Eigen::MatrixXd &MTheta)
-
void computeAThetaStar(Eigen::MatrixXd &AThetaStar)
-
void computeBThetaStar(Eigen::MatrixXd &BThetaStar)
-
void computeCThetaStar(Eigen::VectorXd &CThetaStar, const Eigen::Vector3d &g_N)
-
void computeBackSubMatrices(BackSubMatrices &backSubContr) const
-
void computeBackSubVectors(BackSubMatrices &backSubContr) const
Private Members
-
int numberOfDegreesOfFreedom = 0
-
std::vector<SpinningBody> spinningBodyVec
-
Eigen::MatrixXd ATheta
-
Eigen::MatrixXd BTheta
-
Eigen::VectorXd CTheta
-
Eigen::Vector3d omega_BN_B = Eigen::Vector3d::Zero()
-
Eigen::MRPd sigma_BN
-
Eigen::Matrix3d dcm_BN = Eigen::Matrix3d::Zero()
-
Eigen::Matrix3d omegaTilde_BN_B = Eigen::Matrix3d::Zero()
-
Eigen::MatrixXd *inertialPositionProperty = nullptr
-
Eigen::MatrixXd *inertialVelocityProperty = nullptr
-
std::string nameOfThetaState = {}
-
std::string nameOfThetaDotState = {}
Private Static Attributes
-
static uint64_t effectorID = 1
-
SpinningBodyNDOFStateEffector()