FormationFlying Module |
![]() |
| AnalyzeVariableTimeDV | Analyze delta-V maneuver sequences with time between burns |
| CheckDeltaVs | Plot the trajectory that will result from a planned maneuver. |
| CompareHills | Compare closed form Hills equations with other methods of propagation. |
| DFFSim | Simulation routine for testing DFF guidance and control laws. |
| DeltaVAnalysis | Compute the total delta-v assoc. w/ several types of reconfigurations. |
| DriftRateSigma | Find the standard deviation of along-track drift per orbit due to rel nav errors. |
| FFEccFrameCompare | Compare two methods of computing the relative motion in an eccentric orbit. |
| FFMaintenancePlotter | Plot the results from "FFMaintenanceSim". |
| FFMaintenanceSim | Formation flying maintenance simulation. |
| FFMaintenanceTests | Returns data associated with various test runs for "FFMaintenanceSim". |
| FindDriftTerm | Find the drift rate term given a probability |
| LPvsCF | Compare the delta-v and trajectory for two methods of relative orbit control. |
| RelativeVelocityError | Compute max. navigation error that maintains the specified performance. |
| TestFFEccLinOrb | Test the FFEccLinOrb function. |
| TestLPCircular | Test the LPEccentric function. |
| TestLPEccentric | Test the LPEccentric function. |
| TestLPEccentricGVE | Test the LPEccentricGVE function. |
| CoarseProb | Coarse collision probability estimate |
| CollProbSet | Calculates the probability of collision given two ellipsoid sets. |
| CollProbVol | Calculates the probability of collision given two ellipsoids using volume relations. |
| CollisionInit | Sample data for collision algorithm initialization. |
| CollisionMonAlg | Collision monitoring algorithm for maneuvering spacecraft. |
| CollisionMonitor | Runs the collision monitoring algorithm. |
| CollisionMonteCarlo | Monte-Carlo analysis of collision probability |
| CollisionSurvey | Runs the collision monitoring algorithm for n maneuvering spacecraft. |
| ConjunctionPlane | Transformation matrix for relative conjunction geometry. |
| DistantPtToEll | Distance from a point to the edge of an ellipsoid. |
| EllipsePatch | 2D elliptical patch, with axes a along x and b along y |
| EllipsePropCirc | Function finds the propagated state uncertainty ellipsoid |
| Ellipsoid | Calculate vertices for an ellipsoid. |
| GenerateTimeVector | Generate a time vector evenly spaced over true anomaly |
| Laguerre | Finds the polynomial roots using Laguerre's method. |
| MinDEllipsoid | Computes the minimum distance between two ellipsoids. |
| Plot3DEllipsoids | Plot collision ellipsoids in 3D |
| PredictCollision | Predict collisions given a new state measurement. |
| RelativeDisturb | Relative disturbances for use with a relative state. |
| VerifyCollStruct | Update computed fields in the collision data structure fields. |
| ViewEllipsoid | Plot collision monitoring ellipsoids. |
| WorstCasePerturbations | Worst-case differential accelerations for spacecraft in formation. |
| ImpulsiveLPManeuver | Computes the delta-v sequence for a relative orbit maneuver. |
| ImpulsiveManeuver | Computes a delta-v sequence for a relative orbit maneuver in a circular orbit |
| InPlane | Computes the delta-v's required for an in-plane maneuver. |
| IterativeImpulsiveManeuver | Iterative impulsive maneuver delta-V |
| LargeFormationControl | Demonstrates control of a large formation of satellites. |
| LinOrbLQG | Generate an LQG controller for linearized relative orbit dynamics. |
| Lyapunov | Compute a constant gain feedback controller for relative orbital motion. |
| OptimalInPlaneDeltaV | Computes the delta-v's and half-orbit delays for an in-plane maneuver. |
| OutOfPlane | Computes the delta-v's required for an out-of-plane maneuver. |
| AddGoals | Add one set of geometric goals to the other. |
| AlignThruster | Computes the desired Hills-to-Body frame quaternion for a thruster firing. |
| CirclePhase | Compute the desired phase on the circle from the desired phase on the ellipse. |
| EllipsePhase | Compute the desired phase on the ellipse from the desired phase on the circle. |
| GetHillsMats | Get Hills transformation matrices |
| GetLVLHMats | Generate LVLH transformation matrices |
| InitializeFormation | Initialize formation orbital states from geometric goals |
| IsCircGeom | Check whether the supplied data structure is for circular geometry or not. |
| IsEccGeom | Check whether the supplied data structure is for eccentric geometry or not. |
| LFState | Leader-follower Hills state |
| PCState | Projected circle state in Hills frame |
| ProjCirc | Calculates orbital elements for projected circular formation. |
| ProjLine | Calculates orbital elements for an in-line formation. |
| QFrenet | Generate the quaternion that transforms from the ECI to the Frenet frame. |
| QHillsToBody | Compute the Hills-to-Body quaternion |
| RotateState | Rotate a geometric state to the circular phase angle phi. |
| ScaleState | Scale a relative state represented by a geometric goal set. This |
| SubGoals | Subtract one set of geometric goals from the other. |
| TeamGoals2Geom | Extract the geometry data from the team goals data structure |
| ThrusterAlignment | Computes body vectors to align with velocity and nadir for a thruster firing. |
| BurnData_Structure | Initialize a burn data structure. |
| Command_Structure | Command data structure for external commands supplied to DFF system. |
| Constraints_Structure | Initialize a constraints data structure. |
| CostEstimate_Structure | Initialize a cost estimate data structure. |
| DeltaVCommand_Structure | Initialize a delta-v command data structure. |
| EccGeometry_Structure | Initialize an eccentric geometry data structure. |
| EccTeamGoals_Structure | Initialize a team goals data structure (for eccentric geometries) |
| Geometry_Structure | Initialize a geometry data structure. |
| ISLMessage_Structure | The ISL message data structure format. |
| Maneuver_Structure | Initialize a maneuver data structure. |
| Orientation_Structure | Initialize an orientation command data structure. |
| PlanningParameters_Structure | Initialize a planning parameters data structure. |
| State_Structure | Initialize a state data structure. |
| TeamGoals_Structure | Initialize a team goals data structure. |
| Team_Structure | Initialize a team data structure. |
| Window_Structure | Initialize a window data structure. |
| AssignmentDemoMvr | Extension of AssignmentDemo to include collision monitoring. |
| AssignmentResults.mat | Saved output from AssignmentDemo for collision monitoring demo. |
| CoarseProbDemo | Coarse probability demo |
| CollDetectSim | Simulation for testing the collision monitoring algorithms. |
| CollMonDemo | Collision monitoring demo. |
| CollisionCompareDemo | Collision monitoring demo: compare CollisionSurvey and coarse methods. |
| DistantPtToEllDemo | Ellipsoid minimum distance demo |
| ReconfigCollisionDemo | Collision monitoring demo for highly eccentric reconfiguration. |
| SampleMvr.mat | Saved maneuver data with 4 burns for collision demos |
| SetProbabilityDemo | Set membership probability demo. Verify shape of function. |
| EccentricControlAnalysis | Analyze the performance of relative orbit control in eccentric orbits |
| ExampleFFAnalysis | Demonstrate the use of FFMaintenanceSim to analyze disturbance effects. |
| LQGEccDemo | Demonstrate LQG control of relative motion in an eccentric orbit |
| LQGOrbitControlDemo | Relative orbit control using LQG |
| RotateStateDemo | Demonstrate the RotateState function |
| TransECIToHills | Two orbits are initialized with a small inclination difference. The orbits |
| FFHEOSolarDist | Simulate relative motion in a HEO orbit with solar pressure disturbance |
| PropagationExample | Compares the relative motion predicted by propagation of the discrete state-space system with the motion predicted by Hills equations. |
| RelativeOrbitSeparation | Relative simulation with accelerations to produce an offset in leader-follower frame. |
| EccTrajDemo | Demonstrate an example relative trajectory with an eccentric reference orbit |
| FFEccAssignmentDemo | Demonstrate the different solutions found by the optimal assignment method and the privileged assignment method, in an eccentric orbit. |
| FFEccInitDemo | Demonstrate how relative motion changes when the same relative state is initialized at different true anomalies. |
| FFEccPropDemo | Compare discrete propagation with continuous solution. |
| FFEccReconfigDemo | Compute several reconfiguation maneuvers of varying duration for an elliptical reference orbit. |
| AssignmentDemo | Demonstrate the different solutions found by the optimal assignment method and the privileged assignment method. |
| DFFReconDemo | Run a formation flying simulation with "DFFSim". |
| RendezvousSim | Demonstrate rendezvous control with PD or LQ |
| LPConvergenceDemo | Examine the "convergence rate" for an impulsive LP solution |
| LPPerformanceDemo | Analyze the performance of the LPEccentric algorithm. |
| SafeEllipseDemo | Demonstrate the safe ellipse for safe relative orbit guidance |
| SafeGuidanceDemo | Demonstrate the performance of Safe Guidance Mode |
| IllustrateEccentricGeometry | Visualization of eccentric relative orbits |
| DiscreteHills | Compute a trajectory from discretized Hills equations |
| FFIntegrate | Integrate two neighboring orbits, with applied relative accelerations |
| HillsEqns | Closed form solution of relative orbital motion using Hills equations. |
| RelativeOrbitRHS | Continuous-time linear model of Hills equations in the Hills frame. |
| ShortArcToHills | Convert short arc measurements to an approximate Hill's state. |
| FFEccDDX | Compute the second derivative of x with respect to true anomaly. |
| FFEccDDY | Compute the second derivative of y with respect to true anomaly. |
| FFEccDDZ | Compute the second derivative of z with respect to true anomaly. |
| FFEccDX | Compute the first derivative of x with respect to true anomaly. |
| FFEccDY | Compute the first derivative of y with respect to true anomaly. |
| FFEccDYDX | Compute the slope of an ellipse, dy/dx, at a particular true anomaly. |
| FFEccDYDX2 | Compute the second derivative of y with respect to x on an ellipse. |
| FFEccDZ | Compute the first derivative of z with respect to true anomaly. |
| DiscreteGVE | Computes the relative state trajectory in an eccentric reference orbit. |
| FFEccDH | Compute integration constant dH for homogeneous solution to LTV diff eqs |
| FFEccDMatPeriodic | Compute velocities for periodic motion in an eccentric orbit |
| FFEccDiscreteHills | Computes the relative state trajectory in an eccentric reference orbit. |
| FFEccGoals | Compute integration constants and initial state given the geometric goals. |
| FFEccH | Compute the H term for the homogeneous solution to LTV diff eqs |
| FFEccIntConst | Integration constants for eccentric relative motion |
| FFEccLawdensEqns | Compute Hills frame state given initial state, true anomaly, and eccentricity |
| FFEccLinOrb | Linearized relative motion in an eccentric reference orbit |
| FFEccProp | Compute Hills frame state at nu given integ. constants and eccentricity. |
| FFEccRMat | Compute the state-transition matrix, R, given the eccentricity and true anomaly. |
| FFEccXExt | Compute extreme x-values and associated true anomalies for given relative motion. |
| FFEccYExt | Compute extreme y-values and associated true anomalies for given relative motion. |
| FFEccZExt | Compute extreme z-values and associated true anomalies for given relative motion. |
| AutoFormGeometry | Autonomously update geometric goals |
| CostMatrixRows | Given the team goals, determines the starting row (a) and ending row (b) |
| DistributeClusterGoals | Given a set of geometric goals for the cluster, with corresponding target |
| EstimateCost | Estimate the (weighted) cost to achieve all specified unique target states. |
| FFEccEstimateCost | Estimate the weighted cost to achieve all specified unique target states |
| FFEccGenerateTeamGoals | Generate a Team Goals data structure given the formation type and size. |
| FFEccHexahedronGeometry | Geometric goals for a hexahedron |
| FFEccTetrahedronGeometry | Goals for tetrahedron geometry in an eccentric orbit. |
| FindMinSet | Find the order of columns in a square matrix which minimizes |
| GenerateTeamGoals | Generate a Team Goals data structure given the formation type and size. |
| InitializeCostMatrix | Given the team goals, initialize the cost matrix "f" with the right size. |
| IsDuplicateState | Determine whether two geometric goal sets are duplicates or not. |
| NearestOffset | Determine the nearest along-track offset for a trajectory that is safe. |
| OptimalAssignment | Compute the optimal configuration for a group of objects. |
| PCGoals | Generate the geometric goals for a cluster in a projected circular formation. |
| PopulateCostMatrix | Fill in a single column of the cost matrix. |
| PrivilegedAssignment | Assign target states to satellites using the privileged assignment method. |
| RestrictIDSet | Given an initial set of relative spacecraft IDs, examine the constraints |
| SetupAssignmentProblem | Set up the parameters for the assignment problem given the team goals struct. |
| SortTeamGoals | Sort the team goals with fixed states listed before variable states. |
| DFFThrusters | Thruster pulsewidth model for DFF. |
| IdealActuator | Ideal actuator |
| CheckAlignment | Post simulation analysis of alignment. |
| MessageAnalysis | Post-simulation message analysis for DFF. |
| TestDFFModules | Test each DFF Module individually, in batch mode. |
| AutoDualPCCommandList | Command list for the following scenario. |
| AutoFormCommandList | Command list for testing autonomous formation and bridging of teams. |
| ClusterGoalsDemoCommandList | Command list for demonstrating the achievement of cluster goals |
| CollisionCommandList | Command list for monitoring a collision. Same as ProjCircCommandList |
| CollisionDemoCommandList | Command list for collision monitoring demo scenario. |
| CollisionDetectCommandList | Command list for Collision Detection Simulation |
| DefaultCommandList | A specific command list is loaded for each simulation run. |
| DemoManeuverCommandList | Command list for the testing the controller. Two spacecraft initialized |
| EccentricTetrahedronCommandList | Command list for achieving a tetrahedron formation in an eccentric orbit |
| MainDemoCommandList | Command list for the main demo. Involves autonomous team formation |
| ProjCircCommandList | Command list for achieving a dual-plane projected circle, |
| SimpleManeuverCommandList | Command list for implementing a simple maneuver with 2 spacecraft. |
| TeamManagementCommandList | Command list for exercising the team management functionality. |
| TestADCSCommandList | Command list for testing the proper function of the ADCS. |
| TestControlCommandList | Command list for the testing the controller. Two spacecraft initialized |
| TestMonitoringCommandList | Command list for Collision Detection Simulation |
| TestOrbAttControlCommandList | Command list for the testing the controller. Two spacecraft initialized |
| TestTeamMgtCommandList | Command list for testing the functionality of the Team Management agent. |
| DFFAttitudeTarget | Generate a reference quaternion for a variety of targets. There |
| DFFControl | The executive function that initializes and runs the DFF software modules. |
| DFFRHS | Right-hand-side of the spacecraft dynamic equations for the DFF system. |
| DFFSimGUI | DFF simulation status GUI. |
| DFFSimulation | Initialize and run a multiple spacecraft simulation with the DFF software. |
| ClusterGoalsTeamOrg.mat | Example cluster goals data |
| DefaultTankData | Generate a data structure for fuel tank info. |
| ParameterUploadDictionary | Load the dictionary of parameters that may be uploaded to the DFF system. |
| SoftwareCommandDictionary | Load the dictionary of known software commands for the DFF system. |
| SpacecraftParameters | Obtain the specified set of fixed spacecraft parameters (for DFF system). |
| TelemetryDictionary | Load the dictionary of telemetry data to be gathered for the DFF system. |
| AutoDualPCSimStruct | Define the simulation data structure for the following scenario. |
| AutoFormSimStruct | Team autonomous formation simulation data structure. |
| ClusterGoalsDemoSimStruct | Cluster goals demo simulation data structure. |
| CollisionDemoSimStruct | ProjCircSimStruct with a new command list to run collision survey. |
| CollisionDetectSimStruct | Collision detection simulation data structure. |
| CollisionSimStruct | ProjCircSimStruct with a new command list to run collision survey. |
| DFFSimStruct | Set up the data structure for a DFF simulation. All inputs are optional. |
| DemoManeuverSimStruct | Set up the data structure for testing the controller. |
| EccentricTetrahedronSimStruct | Eccentric tetrahedron simulation data structure. |
| MainDemoSimStruct | Define the simulation data structure for the main demo |
| ProjCircSimStruct | Projected circle reconfiguration simulation data structure. |
| SimpleManeuverSimStruct | Set up the data structure for testing the controller. |
| TeamManagementSimStruct | Set up the data structure for a Team Management demonstration of the DFF system. |
| TeamOrgDemo.mat | Example data with 5 satellites and 2 teams |
| TestADCSSimStruct | Attitude control test data structure |
| TestCollisionSimStruct | Set up a DFF simulation data structure to demonstrate collision detection |
| TestControlSimStruct | Set up the data structure for testing the controller. |
| TestOrbAttControlSimStruct | Set up the data structure for testing both orbit and attitude control. |
| TestTeamMgtSimStruct | Team management simulation data structure |
| StateSensor | State sensor. Gives the ideal states of the system. |
| DFFAttitudeController | DFF attitude control routine. |
| DFFAttitudeCoordination | The attitude coordination component of the decentralized framework. |
| DFFAttitudeManagement | The attitude management component of the decentralized framework. |
| DFFAttitudeManeuver | DFF attitude maneuver planning |
| DFFCollisionAvoidance | The Collision Avoidance module for the DFF system. |
| DFFCollisionMonitor | The Collision monitoring component for the decentralized framework |
| DFFCommandProcessing | Receive ground commands and route them to the appropriate module(s). |
| DFFControlLaw | The decentralized control law. |
| DFFCoordinateTransformation | The coordinate transformation element of the software. |
| DFFDeltaVManagement | The delta-v management component of the control software. |
| DFFGuidanceLaw | The decentralized guidance law. |
| DFFISLManagement | The ISL management software for the decentralized framework. |
| DFFModuleTemplate | Template for DFF software module. Describe the basic functionality here. |
| DFFParameterDatabase | The parameter database for the decentralized formation flying framework. |
| DFFRelativeNavigation | DFF relative navigation |
| DFFTeamManagement | The team management software for the decentralized satellite framework. |
| LPCircular | Computes the thrust trajectory to go from an initial state x0 |
| LPCircularTimeWeight | Determine the target state on the desired trajectory that gives the minimum |
| LPEccentric | Computes the thrust trajectory to go from an initial state x0 |
| LPEccentricGVE | Computes the thrust trajectory to go from an initial state x0 to a |
| LPEccentricTimeWeight | Determine the target state on the desired trajectory that gives the minimum |
| AlongTrackMotion | Compute attributes of along-track motion from relative state vector |
| AnimateRE | Animate the evolution of the desired "safe ellipse" with the position |
| ComputeRE | Compute a safe 2x1 relative in-plane ellipse. |
| CrossTrackDeltaV | Compute the DV to achieve a min. cross-track dist. at along-track crossing. |
| DeltaVChart | Generate a stacked bar chart showing delta-v directions over time |
| EllipseDeltaV | Compute a delta-v that will change the current relative trajectory to a |
| HillsEqnsSLO | Closed form solution of relative orbital motion using Hills equations. |
| NominalSafeGuidance | The Nominal Safe Guidance method. |
| PlotRun3D | Generate a 3D plot of a relative trajectory. |
| PositionDeltaV | Compute delta-v required to reach a target position, given pos. and vel. |
| RE2Hills | Compute the Hills-frame state associated with a relative ellipse. |
| RE2SLO | Compute the SLO-frame state associated with a relative ellipse. |
| RadialOscillation | Compute the radial oscillation of the relative motion using Hills eqns. |
| RestrictDeltaV | Restrict the in-plane and cross-track components of the delta-v |
| SafeEllipseParams | Compute the "safe ellipse" parameters from relative SLO-frame pos & vel |
| SafeEllipsePosVel | Compute the relative SLO-frame position and velocity that corresponds to |
| SafeGuidance | The Safe Guidance Mode. |
| SafeGuidanceBurnData | Find index values for separation, nominal and cross-track burns. |
| SafeGuidanceParameters | Tunable parameters for Safe Guidance and Collison Detection algorithms |
| SafeGuidanceSim | Relative dynamic simulation for two LEO satellites with safe guidance. |
| SafeGuidanceSimInit | Returns input data for various test cases for SafeGuidanceSim |
| SafeGuidanceSimPlots | Plot select results from a simulation |
| SeparationGuidance | The Separation Guidance method. |
| YRMax | Compute the maximum value of yR |
| AbsRelECI2Hills | Compute a Hills state from a relative ECI state |
| DeltaAlfriend2El | Compute standard differential elements from Alfriend differential elements. |
| DeltaEl2Alfriend | Compute Alfriend differential elements from standard differential elements. |
| DeltaElem2Goals | Reconstructs the geometric goals from the element differences. |
| DeltaElem2Hills | Computes the Hills frame state from orbital element differences and |
| ECI2Hills | Compute the relative state in Hills frame given two ECI state vectors. |
| ECI2LVLH | Compute relative LVLH state from a reference ECI state and ECI state |
| ECI2MeanElements | Computes mean orbital elements from reference ECI position and velocity |
| FFEccDeltaElem2Goals | Convert element differences to eccentric geometric goals. |
| FFEccDeltaElem2Hills | Convert element differences to Hills frame coordinates in an eccentric orbit. |
| FFEccFrenet2Goals | Compute geometric goals given Frenet frame state and orbit info |
| FFEccGoals2Hills | Compute Hills frame state (time-domain) given geometric goals and orbit info |
| FFEccHills2DeltaElem | Compute element differences from Hills frame state and ref. elements |
| FFEccHills2Goals | Compute geometric goals given Hills frame state and orbit info |
| Frenet2Hills | Rotate the Frenet frame state to the Hills frame, where x is radial |
| GeometryCirc2Ecc | Convert a circular geometry structure to an eccentric geometry structure. |
| GeometryEcc2Circ | Convert an eccentric geometry structure to a circular geometry structure. |
| Goals2DeltaElem | Computes the desired orbital element differences, given the formation flying |
| Goals2Hills | Compute a Hills state from geometric goals |
| Hills2DeltaElem | Computes the Hills orbital element differences |
| Hills2ECI | Given the reference state in ECI, converts a Hills frame state to ECI. |
| Hills2Frenet | Rotate the Hills frame state to the Frenet frame, where x is along-track |
| Hills2Goals | Convert Hills state to geometric goals |
| Hills2LVLH | Converts a state vector from the Hills to the LVLH coordinate frame. |
| LVLH2ECI | Given the reference state in ECI, converts an LVLH frame state to ECI. |
| LVLH2Hills | Converts a state vector from the LVLH to the Hills coordinate frame. |
| Mean2Osc | Transforms mean orbital elements to osculating orbital elements. |
| Mean2OscS | Transforms mean orbital elements to osculating orbital elements. |
| Osc2Mean | Transforms osculating orbital elements to mean orbital elements. |
| TransformGeom2Hills | Transform geometric goals to hills-frame coordinates. |
| AccelVector2ManeuverStruct | Build a "maneuver" data structure from acceleration and time vectors. |
| ApplyDeltaV | ------------------------------------------------------------------------- |
| DataSize | Find the size in bytes of a piece of data. |
| FFEccTargetTrueAnom | Compute the future true anomaly (unwrapped) at the specified number of orbits |
| Hexahedron | Compute the 5 points of a regular tetrahedron, the surface area and volume. |
| JD2SS1970 | Converts a Julian Date to seconds since 00:00:00 GMT, Jan. 1, 1970. |
| ManeuverStruct2AccelVector | Compute a 3xN acceleration vector from a "maneuver" data structure. |
| MeanAnom2TrueLat | Convert mean anomaly to true latitude. |
| NOrbVector | Compute a vector of maneuver durations from time window data |
| NewtRaph2 | Newton Raphson solver. |
| Nu2TimeDomain | Convert a relative state from the nu-domain to the time-domain. |
| NuDot | Compute the time-derivative of the true anomaly. |
| RVOrbGenDV | Generate an orbit by propagating Keplerian elements with impulsive delta-vs. |
| SS19702JD | Converts seconds since 00:00:00 GMT, Jan. 1, 1970 to a Julian date. |
| Tetrahedron | Compute the 4 points of a regular tetrahedron, the surface area and volume. |
| Time2NuDomain | Convert a relative state from the time-domain to the nu-domain. |
| TimeUntilTheta | Computes the time in seconds until the latitude "theta2" is reached from the |
| CascadingTetrahedron.fd.mat | Cascading tetrahedron saved formation design file. |
| CostVis | Visualize the cost to achieve each target state on the trajectory. |
| DisplayPlugin | Display Plugin for the Formation Design GUI. |
| FFEccAnalyzeShape | Interactively analyze the shape of a relative trajectory in an eccentric reference orbit. |
| FFEccShapes | Compute the shape of the relative motion in the orbital plane. |
| FormationDesignGUI | Formation Design GUI. |
| GeometryPlugin | Geometry Plugin for the Formation Design GUI. |
| HillsFramePlot | Plot the trajectory in Hills frame and show the x-z, x-y projections. |
| MultiProjCirc.fd.mat | Multi-projected circle saved formation design file. |
| OrbitDataPlugin | Orbit Data Plugin for the Formation Design GUI. |
| RelativeStatePlugin | Relative State Plugin for the Formation Design GUI. |
| SatellitePlugin | Satellite Plugin for the Formation Design GUI. |
| ShowTeams | Graphically show the hierarchy of teams. |
| TeamLevels | Assign a hierarchical level to each team in the array. |
| TeamPlugin | Team Plugin for the Formation Design GUI. |
| ViewFormation | View the 3-D trajectory of a formation in Hills frame. |
| ViewGeometry | View the geometry created by a formation of spacecraft |
| ViewHills | Animation the relative motion in Hills frame. |
| ViewRelativeMotion | View the relative motion for geometric goals |
| ViewRotatingHillsFrame | Animate a satellite's relative trajectory in the inertial frame. |
Back to API main page