Flight Class

class rocketpy.Flight.Flight(rocket, environment, inclination=80, heading=90, initialSolution=None, terminateOnApogee=False, maxTime=600, maxTimeStep=inf, minTimeStep=0, rtol=1e-06, atol=[0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 1e-06, 1e-06, 1e-06, 1e-06, 0.001, 0.001, 0.001], timeOvershoot=True, verbose=False)[source]

Keeps all flight information and has a method to simulate flight.

Other classes
env

Environment object describing rail length, elevation, gravity and weather condition. See Environment class for more details.

Type

Environment

rocket

Rocket class describing rocket. See Rocket class for more details.

Type

Rocket

parachutes

Direct link to parachutes of the Rocket. See Rocket class for more details.

Type

Parachutes

frontalSurfaceWind

Surface wind speed in m/s aligned with the launch rail.

Type

float

lateralSurfaceWind

Surface wind speed in m/s perpendicular to launch rail.

Type

float

Helper classes
flightPhases

Helper class to organize and manage different flight phases.

Type

class

timeNodes

Helper class to manage time discretization during simulation.

Type

class

Helper functions
timeIterator[source]

Helper iterator function to generate time discretization points.

Type

function

Helper parameters
effective1RL

Original rail length minus the distance measured from nozzle exit to the upper rail button. It assumes the nozzle to be aligned with the beginning of the rail.

Type

float

effective2RL

Original rail length minus the distance measured from nozzle exit to the lower rail button. It assumes the nozzle to be aligned with the beginning of the rail.

Type

float

Numerical Integration settings: Flight.maxTime : int, float

Maximum simulation time allowed. Refers to physical time being simulated, not time taken to run simulation.

Flight.maxTimeStepint, float

Maximum time step to use during numerical integration in seconds.

Flight.minTimeStepint, float

Minimum time step to use during numerical integration in seconds.

Flight.rtolint, float

Maximum relative error tolerance to be tolerated in the numerical integration scheme.

Flight.atolint, float

Maximum absolute error tolerance to be tolerated in the integration scheme.

Flight.timeOvershootbool, optional

If True, decouples ODE time step from parachute trigger functions sampling rate. The time steps can overshoot the necessary trigger function evaluation points and then interpolation is used to calculate them and feed the triggers. Can greatly improve run time in some cases.

Flight.terminateOnApogeebool

Whether to terminate simulation when rocket reaches apogee.

Flight.solverscipy.integrate.LSODA

Scipy LSODA integration scheme.

State Space Vector Definition: Flight.x : Function

Rocket’s X coordinate (positive east) as a function of time.

Flight.yFunction

Rocket’s Y coordinate (positive north) as a function of time.

Flight.zFunction

Rocket’s z coordinate (positive up) as a function of time.

Flight.vxFunction

Rocket’s X velocity as a function of time.

Flight.vyFunction

Rocket’s Y velocity as a function of time.

Flight.vzFunction

Rocket’s Z velocity as a function of time.

Flight.e0Function

Rocket’s Euler parameter 0 as a function of time.

Flight.e1Function

Rocket’s Euler parameter 1 as a function of time.

Flight.e2Function

Rocket’s Euler parameter 2 as a function of time.

Flight.e3Function

Rocket’s Euler parameter 3 as a function of time.

Flight.w1Function

Rocket’s angular velocity Omega 1 as a function of time. Direction 1 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry.

Flight.w2Function

Rocket’s angular velocity Omega 2 as a function of time. Direction 2 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry and direction 1.

Flight.w3Function

Rocket’s angular velocity Omega 3 as a function of time. Direction 3 is in the rocket’s body axis and points in the direction of cylindrical symmetry.

Flight.latitude: Function

Rocket’s latitude coordinates (positive North) as a function of time. The Equator has a latitude equal to 0, by convention.

Flight.longitude: Function

Rocket’s longitude coordinates (positive East) as a function of time. Greenwich meridian has a longitude equal to 0, by convention.

Solution attributes: Flight.inclination : int, float

Launch rail inclination angle relative to ground, given in degrees.

Flight.headingint, float

Launch heading angle relative to north given in degrees.

Flight.initialSolutionlist

List defines initial condition - [tInit, xInit, yInit, zInit, vxInit, vyInit, vzInit, e0Init, e1Init, e2Init, e3Init, w1Init, w2Init, w3Init]

Flight.tInitialint, float

Initial simulation time in seconds. Usually 0.

Flight.solutionlist

Solution array which keeps results from each numerical integration.

Flight.tfloat

Current integration time.

Flight.ylist

Current integration state vector u.

Flight.postProcessedbool

Defines if solution data has been post processed.

Solution monitor attributes: Flight.initialSolution : list

List defines initial condition - [tInit, xInit, yInit, zInit, vxInit, vyInit, vzInit, e0Init, e1Init, e2Init, e3Init, w1Init, w2Init, w3Init]

Flight.outOfRailTimeint, float

Time, in seconds, in which the rocket completely leaves the rail.

Flight.outOfRailStatelist

State vector u corresponding to state when the rocket completely leaves the rail.

Flight.outOfRailVelocityint, float

Velocity, in m/s, with which the rocket completely leaves the rail.

Flight.apogeeStatearray

State vector u corresponding to state when the rocket’s vertical velocity is zero in the apogee.

Flight.apogeeTimeint, float

Time, in seconds, in which the rocket’s vertical velocity reaches zero in the apogee.

Flight.apogeeXint, float

X coordinate (positive east) of the center of mass of the rocket when it reaches apogee.

Flight.apogeeYint, float

Y coordinate (positive north) of the center of mass of the rocket when it reaches apogee.

Flight.apogeeint, float

Z coordinate, or altitude, of the center of mass of the rocket when it reaches apogee.

Flight.xImpactint, float

X coordinate (positive east) of the center of mass of the rocket when it impacts ground.

Flight.yImpactint, float

Y coordinate (positive east) of the center of mass of the rocket when it impacts ground.

Flight.impactVelocityint, float

Velocity magnitude of the center of mass of the rocket when it impacts ground.

Flight.impactStatearray

State vector u corresponding to state when the rocket impacts the ground.

Flight.parachuteEventsarray

List that stores parachute events triggered during flight.

Flight.functionEvaluationsarray

List that stores number of derivative function evaluations during numerical integration in cumulative manner.

Flight.functionEvaluationsPerTimeSteparray

List that stores number of derivative function evaluations per time step during numerical integration.

Flight.timeStepsarray

List of time steps taking during numerical integration in seconds.

Flight.flightPhasesFlight.FlightPhases

Stores and manages flight phases.

Solution Secondary Attributes: Atmospheric: Flight.windVelocityX : Function

Wind velocity X (East) experienced by the rocket as a function of time. Can be called or accessed as array.

Flight.windVelocityYFunction

Wind velocity Y (North) experienced by the rocket as a function of time. Can be called or accessed as array.

Flight.densityFunction

Air density experienced by the rocket as a function of time. Can be called or accessed as array.

Flight.pressureFunction

Air pressure experienced by the rocket as a function of time. Can be called or accessed as array.

Flight.dynamicViscosityFunction

Air dynamic viscosity experienced by the rocket as a function of time. Can be called or accessed as array.

Flight.speedOfSoundFunction

Speed of Sound in air experienced by the rocket as a function of time. Can be called or accessed as array.

Kinematics: Flight.ax : Function

Rocket’s X (East) acceleration as a function of time, in m/s². Can be called or accessed as array.

Flight.ayFunction

Rocket’s Y (North) acceleration as a function of time, in m/s². Can be called or accessed as array.

Flight.azFunction

Rocket’s Z (Up) acceleration as a function of time, in m/s². Can be called or accessed as array.

Flight.alpha1Function

Rocket’s angular acceleration Alpha 1 as a function of time. Direction 1 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry. Units of rad/s². Can be called or accessed as array.

Flight.alpha2Function

Rocket’s angular acceleration Alpha 2 as a function of time. Direction 2 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry and direction 1. Units of rad/s². Can be called or accessed as array.

Flight.alpha3Function

Rocket’s angular acceleration Alpha 3 as a function of time. Direction 3 is in the rocket’s body axis and points in the direction of cylindrical symmetry. Units of rad/s². Can be called or accessed as array.

Flight.speedFunction

Rocket velocity magnitude in m/s relative to ground as a function of time. Can be called or accessed as array.

Flight.maxSpeedfloat

Maximum velocity magnitude in m/s reached by the rocket relative to ground during flight.

Flight.maxSpeedTimefloat

Time in seconds at which rocket reaches maximum velocity magnitude relative to ground.

Flight.horizontalSpeedFunction

Rocket’s velocity magnitude in the horizontal (North-East) plane in m/s as a function of time. Can be called or accessed as array.

Flight.AccelerationFunction

Rocket acceleration magnitude in m/s² relative to ground as a function of time. Can be called or accessed as array.

Flight.maxAccelerationfloat

Maximum acceleration magnitude in m/s² reached by the rocket relative to ground during flight.

Flight.maxAccelerationTimefloat

Time in seconds at which rocket reaches maximum acceleration magnitude relative to ground.

Flight.pathAngleFunction

Rocket’s flight path angle, or the angle that the rocket’s velocity makes with the horizontal (North-East) plane. Measured in degrees and expressed as a function of time. Can be called or accessed as array.

Flight.attitudeVectorXFunction

Rocket’s attitude vector, or the vector that points in the rocket’s axis of symmetry, component in the X direction (East) as a function of time. Can be called or accessed as array.

Flight.attitudeVectorYFunction

Rocket’s attitude vector, or the vector that points in the rocket’s axis of symmetry, component in the Y direction (East) as a function of time. Can be called or accessed as array.

Flight.attitudeVectorZFunction

Rocket’s attitude vector, or the vector that points in the rocket’s axis of symmetry, component in the Z direction (East) as a function of time. Can be called or accessed as array.

Flight.attitudeAngleFunction

Rocket’s attitude angle, or the angle that the rocket’s axis of symmetry makes with the horizontal (North-East) plane. Measured in degrees and expressed as a function of time. Can be called or accessed as array.

Flight.lateralAttitudeAngleFunction

Rocket’s lateral attitude angle, or the angle that the rocket’s axis of symmetry makes with plane defined by the launch rail direction and the Z (up) axis. Measured in degrees and expressed as a function of time. Can be called or accessed as array.

Flight.phiFunction

Rocket’s Spin Euler Angle, φ, according to the 3-2-3 rotation system (NASA Standard Aerospace). Measured in degrees and expressed as a function of time. Can be called or accessed as array.

Flight.thetaFunction

Rocket’s Nutation Euler Angle, θ, according to the 3-2-3 rotation system (NASA Standard Aerospace). Measured in degrees and expressed as a function of time. Can be called or accessed as array.

Flight.psiFunction

Rocket’s Precession Euler Angle, ψ, according to the 3-2-3 rotation system (NASA Standard Aerospace). Measured in degrees and expressed as a function of time. Can be called or accessed as array.

Dynamics: Flight.R1 : Function

Resultant force perpendicular to rockets axis due to aerodynamic forces as a function of time. Units in N. Expressed as a function of time. Can be called or accessed as array. Direction 1 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry.

Flight.R2Function

Resultant force perpendicular to rockets axis due to aerodynamic forces as a function of time. Units in N. Expressed as a function of time. Can be called or accessed as array. Direction 2 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry and direction 1.

Flight.R3Function

Resultant force in rockets axis due to aerodynamic forces as a function of time. Units in N. Usually just drag. Expressed as a function of time. Can be called or accessed as array. Direction 3 is in the rocket’s body axis and points in the direction of cylindrical symmetry.

Flight.M1Function

Resultant moment (torque) perpendicular to rockets axis due to aerodynamic forces and eccentricity as a function of time. Units in N*m. Expressed as a function of time. Can be called or accessed as array. Direction 1 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry.

Flight.M2Function

Resultant moment (torque) perpendicular to rockets axis due to aerodynamic forces and eccentricity as a function of time. Units in N*m. Expressed as a function of time. Can be called or accessed as array. Direction 2 is in the rocket’s body axis and points perpendicular to the rocket’s axis of cylindrical symmetry and direction 1.

Flight.M3Function

Resultant moment (torque) in rockets axis due to aerodynamic forces and eccentricity as a function of time. Units in N*m. Expressed as a function of time. Can be called or accessed as array. Direction 3 is in the rocket’s body axis and points in the direction of cylindrical symmetry.

Flight.aerodynamicLiftFunction

Resultant force perpendicular to rockets axis due to aerodynamic effects as a function of time. Units in N. Expressed as a function of time. Can be called or accessed as array.

Flight.aerodynamicDragFunction

Resultant force aligned with the rockets axis due to aerodynamic effects as a function of time. Units in N. Expressed as a function of time. Can be called or accessed as array.

Flight.aerodynamicBendingMomentFunction

Resultant moment perpendicular to rocket’s axis due to aerodynamic effects as a function of time. Units in N m. Expressed as a function of time. Can be called or accessed as array.

Flight.aerodynamicSpinMomentFunction

Resultant moment aligned with the rockets axis due to aerodynamic effects as a function of time. Units in N m. Expressed as a function of time. Can be called or accessed as array.

Flight.railButton1NormalForceFunction

Upper rail button normal force in N as a function of time. Can be called or accessed as array.

Flight.maxRailButton1NormalForcefloat

Maximum upper rail button normal force experienced during rail flight phase in N.

Flight.railButton1ShearForceFunction

Upper rail button shear force in N as a function of time. Can be called or accessed as array.

Flight.maxRailButton1ShearForcefloat

Maximum upper rail button shear force experienced during rail flight phase in N.

Flight.railButton2NormalForceFunction

Lower rail button normal force in N as a function of time. Can be called or accessed as array.

Flight.maxRailButton2NormalForcefloat

Maximum lower rail button normal force experienced during rail flight phase in N.

Flight.railButton2ShearForceFunction

Lower rail button shear force in N as a function of time. Can be called or accessed as array.

Flight.maxRailButton2ShearForcefloat

Maximum lower rail button shear force experienced during rail flight phase in N.

Flight.rotationalEnergyFunction

Rocket’s rotational kinetic energy as a function of time. Units in J.

Flight.translationalEnergyFunction

Rocket’s translational kinetic energy as a function of time. Units in J.

Flight.kineticEnergyFunction

Rocket’s total kinetic energy as a function of time. Units in J.

Flight.potentialEnergyFunction

Rocket’s gravitational potential energy as a function of time. Units in J.

Flight.totalEnergyFunction

Rocket’s total mechanical energy as a function of time. Units in J.

Flight.thrustPowerFunction

Rocket’s engine thrust power output as a function of time in Watts. Can be called or accessed as array.

Flight.dragPowerFunction

Aerodynamic drag power output as a function of time in Watts. Can be called or accessed as array.

Stability and Control: Flight.attitudeFrequencyResponse : Function

Fourier Frequency Analysis of the rocket’s attitude angle. Expressed as the absolute vale of the magnitude as a function of frequency in Hz. Can be called or accessed as array.

Flight.omega1FrequencyResponseFunction

Fourier Frequency Analysis of the rocket’s angular velocity omega 1. Expressed as the absolute vale of the magnitude as a function of frequency in Hz. Can be called or accessed as array.

Flight.omega2FrequencyResponseFunction

Fourier Frequency Analysis of the rocket’s angular velocity omega 2. Expressed as the absolute vale of the magnitude as a function of frequency in Hz. Can be called or accessed as array.

Flight.omega3FrequencyResponseFunction

Fourier Frequency Analysis of the rocket’s angular velocity omega 3. Expressed as the absolute vale of the magnitude as a function of frequency in Hz. Can be called or accessed as array.

Flight.staticMarginFunction

Rocket’s static margin during flight in calibers.

Fluid Mechanics: Flight.streamVelocityX : Function

Freestream velocity x (East) component, in m/s, as a function of time. Can be called or accessed as array.

Flight.streamVelocityYFunction

Freestream velocity y (North) component, in m/s, as a function of time. Can be called or accessed as array.

Flight.streamVelocityZFunction

Freestream velocity z (up) component, in m/s, as a function of time. Can be called or accessed as array.

Flight.freestreamSpeedFunction

Freestream velocity magnitude, in m/s, as a function of time. Can be called or accessed as array.

Flight.apogeeFreestreamSpeedfloat

Freestream speed of the rocket at apogee in m/s.

Flight.MachNumberFunction

Rocket’s Mach number defined as its freestream speed divided by the speed of sound at its altitude. Expressed as a function of time. Can be called or accessed as array.

Flight.maxMachNumberfloat

Rocket’s maximum Mach number experienced during flight.

Flight.maxMachNumberTimefloat

Time at which the rocket experiences the maximum Mach number.

Flight.ReynoldsNumberFunction

Rocket’s Reynolds number, using its diameter as reference length and freestreamSpeed as reference velocity. Expressed as a function of time. Can be called or accessed as array.

Flight.maxReynoldsNumberfloat

Rocket’s maximum Reynolds number experienced during flight.

Flight.maxReynoldsNumberTimefloat

Time at which the rocket experiences the maximum Reynolds number.

Flight.dynamicPressureFunction

Dynamic pressure experienced by the rocket in Pa as a function of time, defined by 0.5*rho*V^2, where rho is air density and V is the freestream speed. Can be called or accessed as array.

Flight.maxDynamicPressurefloat

Maximum dynamic pressure, in Pa, experienced by the rocket.

Flight.maxDynamicPressureTimefloat

Time at which the rocket experiences maximum dynamic pressure.

Flight.totalPressureFunction

Total pressure experienced by the rocket in Pa as a function of time. Can be called or accessed as array.

Flight.maxTotalPressurefloat

Maximum total pressure, in Pa, experienced by the rocket.

Flight.maxTotalPressureTimefloat

Time at which the rocket experiences maximum total pressure.

Flight.angleOfAttackFunction

Rocket’s angle of attack in degrees as a function of time. Defined as the minimum angle between the attitude vector and the freestream velocity vector. Can be called or accessed as array.

Fin Flutter Analysis: Flight.flutterMachNumber: Function

The freestream velocity at which begins flutter phenomenon in rocket’s fins. It’s expressed as a function of the air pressure experienced for the rocket. Can be called or accessed as array.

Flight.difference: Function

Difference between flutterMachNumber and machNumber, as a function of time.

Flight.safetyFactor: Function

Ratio between the flutterMachNumber and machNumber, as a function of time.

Run a trajectory simulation.

Parameters
  • rocket (Rocket) – Rocket to simulate. See help(Rocket) for more information.

  • environment (Environment) – Environment to run simulation on. See help(Environment) for more information.

  • inclination (int, float, optional) – Rail inclination angle relative to ground, given in degrees. Default is 80.

  • heading (int, float, optional) – Heading angle relative to north given in degrees. Default is 90, which points in the x direction.

  • initialSolution (array, optional) –

    Initial solution array to be used. Format is initialSolution = [self.tInitial,

    xInit, yInit, zInit, vxInit, vyInit, vzInit, e0Init, e1Init, e2Init, e3Init, w1Init, w2Init, w3Init].

    If None, the initial solution will start with all null values, except for the euler parameters which will be calculated based on given values of inclination and heading. Default is None.

  • terminateOnApogee (boolean, optional) – Whether to terminate simulation when rocket reaches apogee. Default is False.

  • maxTime (int, float, optional) – Maximum time in which to simulate trajectory in seconds. Using this without setting a maxTimeStep may cause unexpected errors. Default is 600.

  • maxTimeStep (int, float, optional) – Maximum time step to use during integration in seconds. Default is 0.01.

  • minTimeStep (int, float, optional) – Minimum time step to use during integration in seconds. Default is 0.01.

  • rtol (float, array, optional) – Maximum relative error tolerance to be tolerated in the integration scheme. Can be given as array for each state space variable. Default is 1e-3.

  • atol (float, optional) – Maximum absolute error tolerance to be tolerated in the integration scheme. Can be given as array for each state space variable. Default is 6*[1e-3] + 4*[1e-6] + 3*[1e-3].

  • timeOvershoot (bool, optional) – If True, decouples ODE time step from parachute trigger functions sampling rate. The time steps can overshoot the necessary trigger function evaluation points and then interpolation is used to calculate them and feed the triggers. Can greatly improve run time in some cases. Default is True.

  • verbose (bool, optional) – If true, verbose mode is activated. Default is False.

Returns

Return type

None

uDotRail1(t, u, postProcessing=False)[source]

Calculates derivative of u state vector with respect to time when rocket is flying in 1 DOF motion in the rail.

Parameters
  • t (float) – Time in seconds

  • u (list) – State vector defined by u = [x, y, z, vx, vy, vz, e0, e1, e2, e3, omega1, omega2, omega3].

  • postProcessing (bool, optional) – If True, adds flight data information directly to self variables such as self.attackAngle. Default is False.

Returns

uDot – State vector defined by uDot = [vx, vy, vz, ax, ay, az, e0Dot, e1Dot, e2Dot, e3Dot, alpha1, alpha2, alpha3].

Return type

list

uDotRail2(t, u, postProcessing=False)[source]

[Still not implemented] Calculates derivative of u state vector with respect to time when rocket is flying in 3 DOF motion in the rail.

Parameters
  • t (float) – Time in seconds

  • u (list) – State vector defined by u = [x, y, z, vx, vy, vz, e0, e1, e2, e3, omega1, omega2, omega3].

  • postProcessing (bool, optional) – If True, adds flight data information directly to self variables such as self.attackAngle, by default False

Returns

uDot – State vector defined by uDot = [vx, vy, vz, ax, ay, az, e0Dot, e1Dot, e2Dot, e3Dot, alpha1, alpha2, alpha3].

Return type

list

uDot(t, u, postProcessing=False)[source]

Calculates derivative of u state vector with respect to time when rocket is flying in 6 DOF motion during ascent out of rail and descent without parachute.

Parameters
  • t (float) – Time in seconds

  • u (list) – State vector defined by u = [x, y, z, vx, vy, vz, e0, e1, e2, e3, omega1, omega2, omega3].

  • postProcessing (bool, optional) – If True, adds flight data information directly to self variables such as self.attackAngle, by default False

Returns

uDot – State vector defined by uDot = [vx, vy, vz, ax, ay, az, e0Dot, e1Dot, e2Dot, e3Dot, alpha1, alpha2, alpha3].

Return type

list

uDotParachute(t, u, postProcessing=False)[source]

Calculates derivative of u state vector with respect to time when rocket is flying under parachute. A 3 DOF approximation is used.

Parameters
  • t (float) – Time in seconds

  • u (list) – State vector defined by u = [x, y, z, vx, vy, vz, e0, e1, e2, e3, omega1, omega2, omega3].

  • postProcessing (bool, optional) – If True, adds flight data information directly to self variables such as self.attackAngle. Default is False.

Returns

uDot – State vector defined by uDot = [vx, vy, vz, ax, ay, az, e0Dot, e1Dot, e2Dot, e3Dot, alpha1, alpha2, alpha3].

Return type

list

solutionArray

Returns solution array of the rocket flight.

time

Returns time array from solution.

x

Rocket x position as a rocketpy.Function of time.

y

Rocket y position as a rocketpy.Function of time.

z

Rocket z position as a rocketpy.Function of time.

vx

Rocket x velocity as a rocketpy.Function of time.

vy

Rocket y velocity as a rocketpy.Function of time.

vz

Rocket z velocity as a rocketpy.Function of time.

e0

Rocket quaternion e0 as a rocketpy.Function of time.

e1

Rocket quaternion e1 as a rocketpy.Function of time.

e2

Rocket quaternion e2 as a rocketpy.Function of time.

e3

Rocket quaternion e3 as a rocketpy.Function of time.

w1

Rocket angular velocity ω1 as a rocketpy.Function of time.

w2

Rocket angular velocity ω2 as a rocketpy.Function of time.

w3

Rocket angular velocity ω3 as a rocketpy.Function of time.

ax

Rocket x acceleration as a rocketpy.Function of time.

ay

Rocket y acceleration as a rocketpy.Function of time.

az

Rocket z acceleration as a rocketpy.Function of time.

alpha1

Rocket angular acceleration α1 as a rocketpy.Function of time.

alpha2

Rocket angular acceleration α2 as a rocketpy.Function of time.

alpha3

Rocket angular acceleration α3 as a rocketpy.Function of time.

R1

Aerodynamic force along the first axis that is perpendicular to the rocket’s axis of symmetry as a rocketpy.Function of time.

R2

Aerodynamic force along the second axis that is perpendicular to the rocket’s axis of symmetry as a rocketpy.Function of time.

R3

Aerodynamic force along the rocket’s axis of symmetry as a rocketpy.Function of time.

M1

Aerodynamic bending moment in the same direction as the axis that is perpendicular to the rocket’s axis of symmetry as a rocketpy.Function of time.

M2

Aerodynamic bending moment in the same direction as the axis that is perpendicular to the rocket’s axis of symmetry as a rocketpy.Function of time.

M3

Aerodynamic bending moment in the same direction as the rocket’s axis of symmetry as a rocketpy.Function of time.

pressure

Air pressure felt by the rocket as a rocketpy.Function of time.

density

Air density felt by the rocket as a rocketpy.Function of time.

dynamicViscosity

Air dynamic viscosity felt by the rocket as a rocketpy.Function of time.

speedOfSound

Speed of sound in the air felt by the rocket as a rocketpy.Function of time.

windVelocityX

Wind velocity in the X direction (east) as a rocketpy.Function of time.

windVelocityY

Wind velocity in the y direction (north) as a rocketpy.Function of time.

speed

Rocket speed, or velocity magnitude, as a rocketpy.Function of time.

maxSpeedTime

Time at which the rocket reaches its maximum speed.

maxSpeed

Maximum speed reached by the rocket.

acceleration

Rocket acceleration magnitude as a rocketpy.Function of time.

maxAcceleration

Maximum acceleration reached by the rocket.

maxAccelerationTime

Time at which the rocket reaches its maximum acceleration.

horizontalSpeed

Rocket horizontal speed as a rocketpy.Function of time.

pathAngle

Rocket path angle as a rocketpy.Function of time.

attitudeVectorX

Rocket attitude vector X component as a rocketpy.Function of time.

attitudeVectorY

Rocket attitude vector Y component as a rocketpy.Function of time.

attitudeVectorZ

Rocket attitude vector Z component as a rocketpy.Function of time.

attitudeAngle

Rocket attitude angle as a rocketpy.Function of time.

lateralAttitudeAngle

Rocket lateral attitude angle as a rocketpy.Function of time.

psi

Precession angle as a rocketpy.Function of time.

phi

Spin angle as a rocketpy.Function of time.

theta

Nutation angle as a rocketpy.Function of time.

streamVelocityX

Freestream velocity X component as a rocketpy.Function of time.

streamVelocityY

Freestream velocity Y component as a rocketpy.Function of time.

streamVelocityZ

Freestream velocity Z component as a rocketpy.Function of time.

freestreamSpeed

Freestream speed as a rocketpy.Function of time.

apogeeFreestreamSpeed

Freestream speed at apogee in m/s.

MachNumber

Mach number as a rocketpy.Function of time.

maxMachNumberTime

Time of maximum Mach number.

maxMachNumber

Maximum Mach number.

ReynoldsNumber

Reynolds number as a rocketpy.Function of time.

maxReynoldsNumberTime

Time of maximum Reynolds number.

maxReynoldsNumber

Maximum Reynolds number.

dynamicPressure

Dynamic pressure as a rocketpy.Function of time.

maxDynamicPressureTime

Time of maximum dynamic pressure.

maxDynamicPressure

Maximum dynamic pressure.

maxTotalPressureTime

Time of maximum total pressure.

maxTotalPressure

Maximum total pressure.

aerodynamicLift

Aerodynamic lift force as a rocketpy.Function of time.

aerodynamicDrag

Aerodynamic drag force as a rocketpy.Function of time.

aerodynamicBendingMoment

Aerodynamic bending moment as a rocketpy.Function of time.

aerodynamicSpinMoment

Aerodynamic spin moment as a rocketpy.Function of time.

rotationalEnergy

Rotational kinetic energy as a rocketpy.Function of time.

translationalEnergy

Translational kinetic energy as a rocketpy.Function of time.

kineticEnergy

Total kinetic energy as a rocketpy.Function of time.

potentialEnergy

Potential energy as a rocketpy.Function of time.

totalEnergy

Total mechanical energy as a rocketpy.Function of time.

thrustPower

Thrust power as a rocketpy.Function of time.

dragPower

Drag power as a rocketpy.Function of time.

angleOfAttack

Angle of attack of the rocket with respect to the freestream velocity vector.

omega1FrequencyResponse

Angular velocity 1 frequency response as a rocketpy.Function of frequency, as the rocket leaves the launch rail for 5 seconds of flight.

omega2FrequencyResponse

Angular velocity 2 frequency response as a rocketpy.Function of frequency, as the rocket leaves the launch rail for 5 seconds of flight.

omega3FrequencyResponse

Angular velocity 3 frequency response as a rocketpy.Function of frequency, as the rocket leaves the launch rail for 5 seconds of flight.

attitudeFrequencyResponse

Attitude frequency response as a rocketpy.Function of frequency, as the rocket leaves the launch rail for 5 seconds of flight.

staticMargin

Static margin of the rocket.

railButton1NormalForce

Upper rail button normal force as a rocketpy.Function of time.

railButton1ShearForce

Upper rail button shear force as a rocketpy.Function of time.

railButton2NormalForce

Lower rail button normal force as a rocketpy.Function of time.

railButton2ShearForce

Lower rail button shear force as a rocketpy.Function of time.

maxRailButton1NormalForce

Maximum upper rail button normal force, in Newtons.

maxRailButton1ShearForce

Maximum upper rail button shear force, in Newtons.

maxRailButton2NormalForce

Maximum lower rail button normal force, in Newtons.

maxRailButton2ShearForce

Maximum lower rail button shear force, in Newtons.

drift

Rocket horizontal distance to tha launch point, in meters, as a rocketpy.Function of time.

bearing

Rocket bearing compass, in degrees, as a rocketpy.Function of time.

latitude

Rocket latitude coordinate, in degrees, as a rocketpy.Function of time.

longitude

Rocket longitude coordinate, in degrees, as a rocketpy.Function of time.

retrieve_acceleration_arrays

Retrieve acceleration arrays from the integration scheme

Returns

  • ax (list) – acceleration in x direction

  • ay (list) – acceleration in y direction

  • az (list) – acceleration in z direction

  • alpha1 (list) – angular acceleration in x direction

  • alpha2 (list) – angular acceleration in y direction

  • alpha3 (list) – angular acceleration in z direction

retrieve_temporary_values_arrays

Retrieve temporary values arrays from the integration scheme. Currently, the following temporary values are retrieved:

  • R1

  • R2

  • R3

  • M1

  • M2

  • M3

  • pressure

  • density

  • dynamicViscosity

  • speedOfSound

Parameters

None

Returns

  • self.R1_list (list) – R1 values

  • self.R2_list (list) – R2 values

  • self.R3_list (list) – R3 values are the aerodynamic force values in the rocket’s axis direction

  • self.M1_list (list) – M1 values

  • self.M2_list (list) – Aerodynamic bending moment in ? direction at each time step

  • self.M3_list (list) – Aerodynamic bending moment in ? direction at each time step

  • self.pressure_list (list) – Air pressure at each time step

  • self.density_list (list) – Air density at each time step

  • self.dynamicViscosity_list (list) – Dynamic viscosity at each time step

  • elf_list._speedOfSound (list) – Speed of sound at each time step

  • self.windVelocityX_list (list) – Wind velocity in x direction at each time step

  • self.windVelocityY_list (list) – Wind velocity in y direction at each time step

calculate_rail_button_forces

Calculate the forces applied to the rail buttons while rocket is still on the launch rail. It will return 0 if no rail buttons are defined.

Returns

  • F11 (Function) – Rail Button 1 force in the 1 direction

  • F12 (Function) – Rail Button 1 force in the 2 direction

  • F21 (Function) – Rail Button 2 force in the 1 direction

  • F22 (Function) – Rail Button 2 force in the 2 direction

postProcess(interpolation='spline', extrapolation='natural')[source]

Post-process all Flight information produced during simulation. Includes the calculation of maximum values, calculation of secondary values such as energy and conversion of lists to Function objects to facilitate plotting.

  • This method is deprecated and is only kept here for backwards compatibility.

  • All attributes that need to be post processed are computed just in time.

Parameters

None

Returns

Return type

None

info()[source]

Prints out a summary of the data available about the Flight.

Parameters

None

Returns

Return type

None

printInitialConditionsData()[source]

Prints all initial conditions data available about the flight

Parameters

None

Returns

Return type

None

printNumericalIntegrationSettings()[source]

Prints out the Numerical Integration settings

Parameters

None

Returns

Return type

None

calculateStallWindVelocity(stallAngle)[source]

Function to calculate the maximum wind velocity before the angle of attack exceeds a desired angle, at the instant of departing rail launch. Can be helpful if you know the exact stall angle of all aerodynamics surfaces.

Parameters

stallAngle (float) – Angle, in degrees, for which you would like to know the maximum wind speed before the angle of attack exceeds it

Returns

Return type

None

plot3dTrajectory()[source]

Plot a 3D graph of the trajectory

Parameters

None

Returns

Return type

None

plotLinearKinematicsData()[source]

Prints out all Kinematics graphs available about the Flight

Parameters

None

Returns

Return type

None

plotAttitudeData()[source]

Prints out all Angular position graphs available about the Flight

Parameters

None

Returns

Return type

None

plotFlightPathAngleData()[source]

Prints out Flight path and Rocket Attitude angle graphs available about the Flight

Parameters

None

Returns

Return type

None

plotAngularKinematicsData()[source]

Prints out all Angular velocity and acceleration graphs available about the Flight

Parameters

None

Returns

Return type

None

plotTrajectoryForceData()[source]

Prints out all Forces and Moments graphs available about the Flight

Parameters

None

Returns

Return type

None

plotEnergyData()[source]

Prints out all Energy components graphs available about the Flight

Returns

Return type

None

plotFluidMechanicsData()[source]

Prints out a summary of the Fluid Mechanics graphs available about the Flight

Parameters

None

Returns

Return type

None

calculateFinFlutterAnalysis(finThickness, shearModulus)[source]

Calculate, create and plot the Fin Flutter velocity, based on the pressure profile provided by Atmospheric model selected. It considers the Flutter Boundary Equation that is based on a calculation published in NACA Technical Paper 4197. Be careful, these results are only estimates of a real problem and may not be useful for fins made from non-isotropic materials. These results should not be used as a way to fully prove the safety of any rocket’s fins. IMPORTANT: This function works if only a single set of fins is added.

Parameters
  • finThickness (float) – The fin thickness, in meters

  • shearModulus (float) – Shear Modulus of fins’ material, must be given in Pascal

Returns

Return type

None

plotStabilityAndControlData()[source]

Prints out Rocket Stability and Control parameters graphs available about the Flight

Parameters

None

Returns

Return type

None

plotPressureSignals()[source]

Prints out all Parachute Trigger Pressure Signals. This function can be called also for plot pressure data for flights without Parachutes, in this case the Pressure Signals will be simply the pressure provided by the atmosphericModel, at Flight z positions. This means that no noise will be considered if at least one parachute has not been added.

This function aims to help the engineer to visually check if there are anomalies with the Flight Simulation.

Parameters

None

Returns

Return type

None

exportPressures(fileName, timeStep)[source]

Exports the pressure experienced by the rocket during the flight to an external file, the ‘.csv’ format is recommended, as the columns will be separated by commas. It can handle flights with or without parachutes, although it is not possible to get a noisy pressure signal if no parachute is added.

If a parachute is added, the file will contain 3 columns: time in seconds, clean pressure in Pascals and noisy pressure in Pascals. For flights without parachutes, the third column will be discarded

This function was created especially for the ‘Projeto Jupiter’ Electronics Subsystems team and aims to help in configuring micro-controllers.

Parameters
  • fileName (string) – The final file name,

  • timeStep (float) – Time step desired for the final file

Returns

Return type

None

exportData(fileName, *variables, timeStep=None)[source]

Exports flight data to a comma separated value file (.csv).

Data is exported in columns, with the first column representing time steps. The first line of the file is a header line, specifying the meaning of each column and its units.

Parameters
  • fileName (string) – The file name or path of the exported file. Example: flight_data.csv. Do not use forbidden characters, such as ‘/’ in Linux/Unix and ‘<, >, :, “, /, , | ?, *’ in Windows.

  • variables (strings, optional) – Names of the data variables which shall be exported. Must be Flight class attributes which are instances of the Function class. Usage example: TestFlight.exportData(‘test.csv’, ‘z’, ‘angleOfAttack’, ‘machNumber’).

  • timeStep (float, optional) – Time step desired for the data. If None, all integration time steps will be exported. Otherwise, linear interpolation is carried out to calculate values at the desired time steps. Example: 0.001.

exportKML(fileName='trajectory.kml', timeStep=None, extrude=True, color='641400F0', altitudeMode='absolute')[source]

Exports flight data to a .kml file, which can be opened with Google Earth to display the rocket’s trajectory.

Parameters
  • fileName (string) – The file name or path of the exported file. Example: flight_data.csv. Do not use forbidden characters, such as ‘/’ in Linux/Unix and ‘<, >, :, “, /, , | ?, *’ in Windows.

  • timeStep (float, optional) – Time step desired for the data. If None, all integration time steps will be exported. Otherwise, linear interpolation is carried out to calculate values at the desired time steps. Example: 0.001.

  • extrude (bool, optional) – To be used if you want to project the path over ground by using an extruded polygon. In case False only the linestring containing the flight path will be created. Default is True.

  • color (str, optional) – Color of your trajectory path, need to be used in specific kml format. Refer to http://www.zonums.com/gmaps/kml_color/ for more info.

  • altitudeMode (str) – Select elevation values format to be used on the kml file. Use ‘relativetoground’ if you want use Above Ground Level elevation, or ‘absolute’ if you want to parse elevation using Above Sea Level. Default is ‘relativetoground’. Only works properly if the ground level is flat. Change to ‘absolute’ if the terrain is to irregular or contains mountains.

Returns

Return type

None

allInfo()[source]

Prints out all data and graphs available about the Flight.

Parameters

None

Returns

Return type

None

animate(start=0, stop=None, fps=12, speed=4, elev=None, azim=None)[source]

Plays an animation of the flight. Not implemented yet. Only kinda works outside notebook.