Module: lambertValidator
Executive Summary
This module computes the required Delta-V to change the spacecraft velocity to the one obtained by the Module: lambertSolver module and checks if the resulting trajectory comes too close to the central body or too far away from the desired target location. The current spacecraft state from the NavTransMsgPayload navigation input message is propagated to the maneuver time \(t_{maneuver}\) using a 4th order Runge-Kutta (RK4) to obtain the expected state just before the Delta-V maneuver. The computed Delta-V and the specified state uncertainty are added to generate a set of initial states right after the maneuver. These initial states are propagated to the final time \(t_{final}\) where the spacecraft is supposed to arrive at the targeted position \({}^N\mathbf{r}_{T/N}\). If the final distance from the target position is less than the specified maximum distance \(r_{TB,max}\) for all trajectories, and none of the trajectories comes closer than \(r_{min}\) to the central body, the computed Delta-V is written to the DvBurnCmdMsgPayload output message. If any of these constraints are violated, the message content remains zero. The message is also zeroed if the LambertSolutionMsgPayload or LambertPerformanceMsgPayload messages indicate that the Lambert solution is not valid or has not converged yet.
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.
Msg Variable Name |
Msg Type |
Description |
---|---|---|
navTransInMsg |
translational navigation input message |
|
lambertProblemInMsg |
lambert problem setup input message |
|
lambertSolutionInMsg |
lambert problem solution input message |
|
lambertPerformanceInMsg |
lambert problem performance message (additional information about the solution process) |
|
dvBurnCmdOutMsg |
Delta-V command output message |
Module Assumptions and Limitations
The equations of motion used inside the module to propagate the state assume simple two body point mass gravity, and the motion is propagated using a 4th order Runge-Kutta (RK4). Additionally, this module assumes that \(t_{final} > t_{maneuver} > t\), with final time \(t_{final}\), maneuver time \(t_{maneuver}\) and current time \(t\).
Algorithm
Equations of motion (two body point mass gravity) with gravitational parameter \(\mu\) and spacecraft position vector \(\mathbf{r}\):
The 27 perturbed initial states that are propagated to check for any constraint violations are obtained in the following way: The uncertainty of each state, specified by the 6x6 matrix “uncertaintyStates” in Hill frame components, is added to each state in the plus and minus direction. For \(N=6\) states, this gives \(2 \times N = 12\) initial states. The uncertainty of the Delta-V magnitude is applied to the Delta-V vector for each of those initial states, both in the Delta-V direction and against the Delta-V direction (corresponding to maximum and minimum expected DV magnitude). Applied to the 12 initial states, this gives 24 states. The last 3 initial states are obtained by applying the maximum and minimum expected DV to the unperturbed spacecraft state (+2), and by leaving the state and Delta-V vector entirely unperturbed (+1).
User Guide
The module is first initialized as follows:
module = lambertValidator.LambertValidator()
module.ModelTag = "lambertValidator"
module.setFinalTime(2000.)
module.setManeuverTime(1000.)
module.setMaxDistanceTarget(3000.)
module.setMinOrbitRadius(6378 * 1000.)
module.setUncertaintyStates(np.diag([5., 5., 5., 0.01, 0.01, 0.001])) # in Hill frame
module.setUncertaintyDV(0.1) # [m/s]
module.setDvConvergenceTolerance(0.01) # [m/s]
unitTestSim.AddModelToTask(unitTaskName, module)
The input messages are then connected:
module.navTransInMsg.subscribeTo(navTransInMsg)
module.lambertProblemInMsg.subscribeTo(lambertProblemInMsg)
module.lambertPerformanceInMsg.subscribeTo(lambertPerformanceInMsg)
module.lambertSolutionInMsg.subscribeTo(lambertSolutionInMsg)
Defines
-
NUM_INITIALSTATES
-
class LambertValidator : public SysModel
- #include <lambertValidator.h>
This module validates if the Lambert velocity solution violates any constraints and, if not, creates the Delta-V burn command message.
Public Functions
-
LambertValidator()
This is the constructor for the module class. It sets default variable values and initializes the various parts of the model
-
~LambertValidator()
Module Destructor
-
void Reset(uint64_t currentSimNanos) override
This method is used to reset the module and checks that required input messages are connected.
- Parameters:
currentSimNanos – current simulation time in nano-seconds
- Returns:
void
-
void UpdateState(uint64_t currentSimNanos) override
This is the main method that gets called every time the module is updated.
- Parameters:
currentSimNanos – current simulation time in nano-seconds
- Returns:
void
-
void setLambertSolutionSpecifier(const double value)
setter for
lambertSolutionSpecifier
-
inline double getLambertSolutionSpecifier() const
getter for
lambertSolutionSpecifier
-
void setFinalTime(const double value)
setter for
finalTime
-
inline double getFinalTime() const
getter for
finalTime
-
void setManeuverTime(const double value)
setter for
maneuverTime
-
inline double getManeuverTime() const
getter for
maneuverTime
-
void setMaxDistanceTarget(const double value)
setter for
maxDistanceTarget
-
inline double getMaxDistanceTarget() const
getter for
maxDistanceTarget
-
void setMinOrbitRadius(const double value)
setter for
minOrbitRadius
-
inline double getMinOrbitRadius() const
getter for
minOrbitRadius
-
void setUncertaintyStates(const Eigen::MatrixXd &value)
setter for
uncertaintyStates
-
inline Eigen::MatrixXd getUncertaintyStates() const
getter for
uncertaintyStates
-
void setUncertaintyDV(const double value)
setter for
uncertaintyDV
-
inline double getUncertaintyDV() const
getter for
uncertaintyDV
-
void setDvConvergenceTolerance(const double value)
setter for
dvConvergenceTolerance
-
inline double getDvConvergenceTolerance() const
getter for
dvConvergenceTolerance
-
void setIgnoreConstraintViolations(const bool value)
setter for
ignoreConstraintViolations
-
inline bool getIgnoreConstraintViolations() const
getter for
ignoreConstraintViolations
Public Members
translational navigation input message
-
ReadFunctor<LambertProblemMsgPayload> lambertProblemInMsg
lambert problem input message
-
ReadFunctor<LambertSolutionMsgPayload> lambertSolutionInMsg
lambert solution input message
-
ReadFunctor<LambertPerformanceMsgPayload> lambertPerformanceInMsg
lambert performance input message
-
Message<DvBurnCmdMsgPayload> dvBurnCmdOutMsg
Delta-V burn command message.
-
Message<LambertValidatorMsgPayload> lambertValidatorOutMsg
Lambert Validator results message.
-
BSKLogger bskLogger
BSK Logging.
Private Functions
-
void readMessages()
This method reads the input messages each call of updateState. It also checks if the message contents are valid for this module.
- Returns:
void
-
void writeMessages(uint64_t currentSimNanos)
This method writes the output messages each call of updateState
- Parameters:
currentSimNanos – current simulation time in nano-seconds
- Returns:
void
-
std::array<Eigen::VectorXd, NUM_INITIALSTATES> getInitialStates()
This method creates the initial state vectors that will be propagated by the module
- Returns:
std::array<Eigen::VectorXd, NUM_INITIALSTATES>
-
void countViolations(std::array<Eigen::VectorXd, NUM_INITIALSTATES> initialStates)
This method propagates the various initial states and counts the number of constraints that are violated
- Parameters:
initialStates – array of initial state vectors to be propagated
- Returns:
void
-
void checkConstraintViolations(std::vector<double> t, std::vector<Eigen::VectorXd> X)
This method checks if the provided trajectory violates any constraints
- Parameters:
t – time steps
X – state for each time step
- Returns:
void
-
bool checkPerformance() const
This method returns true only if the Lambert solution is valid, converged, and no constraints are violated
- Returns:
bool
-
std::pair<std::vector<double>, std::vector<Eigen::VectorXd>> propagate(const std::function<Eigen::VectorXd(double, Eigen::VectorXd)> &EOM, std::array<double, 2> interval, const Eigen::VectorXd &X0, double dt)
This method integrates the provided equations of motion using Runge-Kutta 4 (RK4) and returns the time steps and state vectors at each time step.
- Parameters:
EOM – equations of motion function to be propagated
interval – integration interval
X0 – initial state
dt – time step
- Returns:
std::pair<std::vector<double>, std::vector<Eigen::VectorXd>>
-
Eigen::VectorXd RK4(const std::function<Eigen::VectorXd(double, Eigen::VectorXd)> &ODEfunction, const Eigen::VectorXd &X0, double t0, double dt)
This method provides the 4th order Runge-Kutta (RK4)
- Parameters:
ODEfunction – function handle that includes the equations of motion
X0 – initial state
t0 – initial time
dt – time step
- Returns:
Eigen::VectorXd
Private Members
-
double lambertSolutionSpecifier = 1
[-] which Lambert solution (1 or 2), if applicable, should be used
-
double finalTime = {}
[s] time at which target position should be reached
-
double maneuverTime = {}
[s] time at which maneuver should be executed
-
double maxDistanceTarget = {}
[m] maximum acceptable distance from target location at final time
-
double minOrbitRadius = {}
[m] minimum acceptable orbit radius
-
Eigen::MatrixXd uncertaintyStates
6x6 matrix square root of the covariance matrix of errors, in Hill frame
-
double uncertaintyDV = 0.1
[m/s] uncertainty of the Delta-V magnitude
-
double dvConvergenceTolerance = 1e-3
[m/s] tolerance on difference between DeltaV solutions between time steps
-
bool ignoreConstraintViolations = false
override flag to write DV message despite constraint violations
-
double time = {}
[s] Current vehicle time-tag associated with measurements
-
Eigen::Vector3d r_N
[m] Current inertial spacecraft position vector in inertial frame N components
-
Eigen::Vector3d v_N
[m/s] Current inertial velocity of the spacecraft in inertial frame N components
-
double mu = {}
[m^3 s^-2] gravitational parameter
-
Eigen::Vector3d r_TN_N
[m] Targeted position vector with respect to celestial body at finalTime, in N frame
-
Eigen::Vector3d vLambert_N
[m/s] Lambert velocity solution at maneuver time in inertial frame N components
-
int validLambert = {}
[-] valid Lambert solution if 1, not if 0
-
double xLambert = {}
[-] solution for free variable (iteration variable) of Lambert problem
-
int numIterLambert = {}
[-] number of root-finder iterations to find x
-
double errXLambert = {}
[-] difference in x between last and second-to-last iteration
-
double prevLambertSolutionX = 0
[-] solution of Lambert problem from previous time step
-
Eigen::Vector3d prevDv_N = {}
solution for Delta-V from previous time step
-
Eigen::Vector3d rm_N
[m] Expected inertial spacecraft position vector at maneuver time tm in inertial frame N
-
Eigen::Vector3d vm_N
[m/s] Expected inertial spacecraft velocity vector at maneuver time tm in inertial frame
-
Eigen::Vector3d dv_N
[m/s] requested Delta-V in N frame components
-
Eigen::Matrix3d dcm_HN
[-] direction cosine matrix (DCM) from inertial frame N to Hill frame H
-
int violationsDistanceTarget = 0
[-] number of violations of the maxDistanceTarget constraint
-
int violationsOrbitRadius = 0
[-] number of violations of the minOrbitRadius constraint
-
double timestep = 10.
[s] time step used for RK4 propagation
-
std::function<Eigen::VectorXd(double, Eigen::VectorXd)> EOM_2BP
equations of motion to be used for RK4
-
int maxNumIterLambert = 6
[-] maximum number of iterations for Lambert solver root finder to find x
-
double xToleranceLambert = 1e-8
[-] tolerance for Lambert solver root finder to find x
-
double xConvergenceTolerance = 1e-2
[-] tolerance on difference between x solutions between time steps
-
LambertValidator()