Module: linearTranslationOneDOFStateEffector
Executive Summary
The linear translation body class is an instantiation of the state effector abstract class. The integrated test is validating the interaction between the linear translation body module and the rigid body hub that it is attached to. In this case, a 1-DoF linear translation body has an inertia tensor and is attached to the hub by a single degree of freedom axis. The spinning axis is fixed in the body frame and the effector is rigid, which means that its center of mass location does not move in the F frame. An optional motor force can be applied on the spinning axis, and the user can also lock the axis through a command.
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 |
---|---|---|
translatingBodyOutMsg |
Output message containing the linear translation body state displacement and displacement rate |
|
motorForceInMsg |
(Optional) Input message of the motor force value |
|
motorLockInMsg |
(Optional) Input message for locking the axis |
|
translatingBodyRefInMsg |
(Optional) Input message for prescribing the displacement and displacement rate |
|
translatingBodyConfigLogOutMsg |
Output message containing the translating body inertial position and attitude states |
Detailed Module Description
A 1 DoF translating body has 2 states: rho
and rhoDot
. The displacemet and displacement rate can change due to the interaction with the hub, but also because of applied forces (control, spring and damper). The displacement remains fixed and the displacement rate is set to zero when the axis is locked.
Mathematical Modeling
See the following tech report for a detailed description of this model.
Note
P. Johnson and J. Vaz Carneiro, “Single Axis Translating Effector,” Technical Note, University of Colorado, Autonomous Vehicle Systems (AVS) Lab, Boulder, CO, March 9, 2024.
User Guide
This section is to outline the steps needed to setup a Translating Body State Effector in Python using Basilisk.
Import the linearTranslatingBodyOneDOFStateEffector class:
from Basilisk.simulation import linearTranslatingBodyOneDOFStateEffector
Create an instantiation of a Translating body:
translatingBody = linearTranslatingBodyOneDOFStateEffector.linearTranslatingBodyOneDOFStateEffector()
Define all physical parameters for a Translating Body. For example:
translatingBody.setMass(20.0) translatingBody.setFHat_B([[3.0 / 5.0], [4.0 / 5.0], [0.0]]) translatingBody.setR_FcF_F([[-1.0], [1.0], [0.0]]) translatingBody.setR_F0B_B([[-5.0], [4.0], [3.0]]) translatingBody.setIPntFc_F([[50.0, 0.0, 0.0], [0.0, 80.0, 0.0], [0.0, 0.0, 60.0]]) translatingBody.setDCM_FB([[0.0, -1.0, 0.0], [0.0, 0.0, -1.0], [1.0, 0.0, 0.0]])
(Optional) Define initial conditions of the effector. Default values are zero states:
translatingBody.setRhoInit(1.0) translatingBody.setRhoDotInit(0.05)
(Optional) Define spring and damper coefficients. Default values are zero:
translatingBody.setK(100.0) translatingBody.setC(0.0)
(Optional) Define a unique name for each state. If you have multiple translating 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:
translatingBody.nameOfThetaState = "translatingBodyRho" translatingBody.nameOfThetaDotState = "translatingBodyRhoDot"
(Optional) Connect a command force message:
cmdArray = messaging.ArrayMotorForceMsgPayload() cmdArray.motorForce = [cmdForce] # [Nm] cmdMsg = messaging.ArrayMotorForceMsg().write(cmdArray) translatingBody.motorForceInMsg.subscribeTo(cmdMsg)
(Optional) Connect an axis-locking message (0 means the axis is free to move and 1 locks the axis):
lockArray = messaging.ArrayEffectorLockMsgPayload() lockArray.effectorLockFlag = [1] lockMsg = messaging.ArrayEffectorLockMsg().write(lockArray) translatingBody.motorLockInMsg.subscribeTo(lockMsg)
(Optional) Connect a displacement and displacement rate reference message:
translationRef = messaging.LinearTranslationRigidBodyMsgPayload() translationRef.rho = 0.2 translationRef.rhoDot = 0.0 translationRefMsg = messaging.LinearTranslationRigidBodyMsg().write(translationRef) translatingBody.translatingBodyRefInMsg.subscribeTo(translationRefMsg)
The linear states of the body are created using an output message
translatingBodyOutMsg
.The translating body config log state output message is
translatingBodyConfigLogOutMsg
.Add the effector to your spacecraft:
scObject.addStateEffector(translatingBody)
See Module: spacecraft documentation on how to set up a spacecraft object.
Add the module to the task list:
unitTestSim.AddModelToTask(unitTaskName, translatingBody)
-
class linearTranslationOneDOFStateEffector : public StateEffector, public SysModel
- #include <linearTranslationOneDOFStateEffector.h>
linear spring mass damper state effector class
Public Functions
-
linearTranslationOneDOFStateEffector()
Constructor.
-
~linearTranslationOneDOFStateEffector()
Destructor.
-
void setMass(double mass)
setter for
mass
property
-
void setK(double k)
setter for
k
property
-
void setC(double c)
setter for
c
property
-
inline void setRhoInit(double rhoInit)
setter for
rhoInit
property
-
inline void setRhoDotInit(double rhoDotInit)
setter for
rhoDotInit
property
-
void setFHat_B(Eigen::Vector3d fHat_B)
setter for
fHat_B
property
-
inline void setR_FcF_F(Eigen::Vector3d r_FcF_F)
setter for
r_FcF_F
property
-
inline void setR_F0B_B(Eigen::Vector3d r_F0B_B)
setter for
r_F0B_B
property
-
inline void setIPntFc_F(Eigen::Matrix3d IPntFc_F)
setter for
IPntFc_F
property
-
inline void setDCM_FB(Eigen::Matrix3d dcm_FB)
setter for
dcm_FB
property
-
inline double getMass() const
setter for
mass
property
-
inline double getK() const
setter for
k
property
-
inline double getC() const
setter for
c
property
-
inline double getRhoInit() const
setter for
rhoInit
property
-
inline double getRhoDotInit() const
setter for
rhoDotInit
property
-
inline Eigen::Vector3d getFHat_B() const
setter for
fHat_B
property
-
inline Eigen::Vector3d getR_FcF_F() const
setter for
r_FcF_F
property
-
inline Eigen::Vector3d getR_F0B_B() const
setter for
r_F0B_B
property
-
inline Eigen::Matrix3d getIPntFc_F() const
setter for
IPntFc_F
property
-
inline Eigen::Matrix3d getDCM_FB() const
setter for
dcm_FB
property
Public Members
-
Message<LinearTranslationRigidBodyMsgPayload> translatingBodyOutMsg
state output message
-
Message<SCStatesMsgPayload> translatingBodyConfigLogOutMsg
translating body state config log message
-
ReadFunctor<ArrayMotorForceMsgPayload> motorForceInMsg
(optional) motor force input message
-
ReadFunctor<LinearTranslationRigidBodyMsgPayload> translatingBodyRefInMsg
(optional) reference state input message
-
ReadFunctor<ArrayEffectorLockMsgPayload> motorLockInMsg
(optional) lock flag input message
Private Functions
-
void Reset(uint64_t CurrentClock) override
-
void registerStates(DynParamManager &states) override
-
void linkInStates(DynParamManager &states) override
-
void writeOutputStateMessages(uint64_t CurrentSimNanos) override
-
void updateEffectorMassProps(double integTime) override
-
void updateContributions(double integTime, BackSubMatrices &backSubContr, Eigen::Vector3d sigma_BN, Eigen::Vector3d omega_BN_B, Eigen::Vector3d g_N) override
-
void updateEnergyMomContributions(double integTime, Eigen::Vector3d &rotAngMomPntCContr_B, double &rotEnergyContr, Eigen::Vector3d omega_BN_B) override
-
void computeDerivatives(double integTime, Eigen::Vector3d rDDot_BN_N, Eigen::Vector3d omegaDot_BN_B, Eigen::Vector3d sigma_BN) override
-
void UpdateState(uint64_t CurrentSimNanos) override
-
void computeTranslatingBodyInertialStates()
-
void computeBackSubContributions(BackSubMatrices &backSubContr, const Eigen::Vector3d &F_g)
-
void readInputMessages()
Private Members
-
double mass = 1.0
[kg] mass of effector
-
double k = 0
[N/m] linear spring constant
-
double c = 0
[N-s/m] linear damping term
-
double rhoInit = 0
[m] initial displacement offset
-
double rhoDotInit = 0
[m/s] Initial displacement rate offset
-
Eigen::Vector3d fHat_B = {1.0, 0.0, 0.0}
unit vector axis of translation in B frame components.
-
Eigen::Vector3d r_FcF_F = Eigen::Vector3d::Zero()
[m] vector pointing from location F to FC in F frame components
-
Eigen::Vector3d r_F0B_B = Eigen::Vector3d::Zero()
[m] vector pointing from body frame B origin to point to F0 origin of F frame in B frame components
-
Eigen::Matrix3d IPntFc_F = Eigen::Matrix3d::Identity()
[kg-m^2] Inertia of pc about point Fc in F frame component
-
Eigen::Matrix3d dcm_FB = Eigen::Matrix3d::Identity()
DCM from the F frame to the body frame.
-
std::string nameOfRhoState = {}
Identifier for the rho state data container.
-
std::string nameOfRhoDotState = {}
Identifier for the rhoDot state data container.
-
bool isAxisLocked = false
flag for locking the translation axis
-
double rho = 0.0
[m] displacement from equilibrium
-
double rhoDot = 0.0
[m/s] time derivative of displacement from equilibrium
-
double rhoRef = 0.0
[m] translating body reference position
-
double rhoDotRef = 0.0
[m/s] translating body reference velocity
-
double motorForce = 0.0
[N] optional motor force
-
Eigen::Vector3d r_FcB_B = Eigen::Vector3d::Zero()
[m] position vector from B to center of mass location of effector
-
Eigen::Vector3d r_FcF0_B = Eigen::Vector3d::Zero()
[m] vector pointing from point p0 origin of F frame to center of mass location of effector in B frame components
-
Eigen::Matrix3d rTilde_FcF_B = Eigen::Matrix3d::Zero()
[m] tilde matrix of r_FcF_B
-
Eigen::Vector3d rPrime_FcF_B = Eigen::Vector3d::Zero()
[m/s] Body time derivative of r_FcF_B
-
Eigen::Matrix3d rPrimeTilde_FcF_B = Eigen::Matrix3d::Zero()
[m/s] Tilde matrix of rPrime_FcF_B
-
Eigen::Matrix3d rTilde_FcB_B = Eigen::Matrix3d::Zero()
[m] tilde matrix of r_FcB_B
-
Eigen::Vector3d rPrime_FcB_B = Eigen::Vector3d::Zero()
[m/s] Body time derivative of r_FcB_B
-
Eigen::Matrix3d rPrimeTilde_FcB_B = Eigen::Matrix3d::Zero()
[m/s] Tilde matrix of rPrime_FcB_B
-
Eigen::Matrix3d IPntFc_B = Eigen::Matrix3d::Identity()
[kg-m^2] Inertia of Fc about point B in B frame components
-
Eigen::Matrix3d dcm_BN = Eigen::Matrix3d::Identity()
DCM from the B frame to the N frame.
-
Eigen::Vector3d omega_BN_B = Eigen::Vector3d::Zero()
[rad/s] angular velocity of the B frame wrt the N frame in B frame components.
-
Eigen::Matrix3d omegaTilde_BN_B = Eigen::Matrix3d::Zero()
[rad/s] tilde matrix of omega_BN_B
-
Eigen::Vector3d aRho = Eigen::Vector3d::Zero()
Term needed for back-sub method.
-
Eigen::Vector3d bRho = Eigen::Vector3d::Zero()
Term needed for back-sub method.
-
double cRho = 0.0
Term needed for back-sub method.
-
Eigen::MatrixXd *g_N = nullptr
[m/s^2] gravitational acceleration in N frame components
-
Eigen::MatrixXd *inertialPositionProperty = nullptr
[m] r_N inertial position relative to system spice zeroBase/refBase
-
Eigen::MatrixXd *inertialVelocityProperty = nullptr
[m] v_N inertial velocity relative to system spice zeroBase/refBase
-
Eigen::Vector3d r_FcN_N = Eigen::Vector3d::Zero()
[m] position vector of translating body’s center of mass Fc relative to the inertial frame origin N
-
Eigen::Vector3d v_FcN_N = Eigen::Vector3d::Zero()
[m/s] inertial velocity vector of Fc relative to inertial frame
-
Eigen::Vector3d sigma_FN = Eigen::Vector3d::Zero()
MRP attitude of frame F relative to inertial frame.
-
Eigen::Vector3d omega_FN_F = Eigen::Vector3d::Zero()
[rad/s] inertial translating body frame angular velocity vector
Private Static Attributes
-
static uint64_t effectorID = 1
ID number of this panel.
-
linearTranslationOneDOFStateEffector()