Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
- Added optional configurable atmosphere-relative velocity computation to ``cannonballDrag`` for improved drag modeling in rotating planetary atmosphere.
Original file line number Diff line number Diff line change
Expand Up @@ -128,10 +128,107 @@ def test_cannonballDrag():
npt.assert_allclose(force_S, F_exp_S, rtol=0.0, atol=1e-12)
npt.assert_allclose(torque_S, T_exp_S, rtol=0.0, atol=1e-12)

def _runCannonballDragAtmoRelVel(useRelVel: bool):
"""Helper that sets up and runs a single-step CannonballDrag test with or without
atmosphere-relative velocity and returns (force_S, torque_S, F_exp_S, T_exp_S)."""
dt = 1 # s

scSim = SimulationBaseClass.SimBaseClass()
dynProcess = scSim.CreateNewProcess("test")
dynProcess.addTask(scSim.CreateNewTask("test", macros.sec2nano(dt)))

density = 2.0 # kg/m^3
cd = 1.5
area = 2.75 # m^2
r_CP_S = [1.0, 0.0, 0.0] # m

v_SN_N = np.array([0.0, 0.5, 0.0]) # m/s
r_SN_N = np.array([7e6, 0.0, 0.0]) # m (only used when useRelVel=True)
sigma_SN = [0.1, 0.2, 0.3]
omega_planet = np.array([0.0, 0.0, orbitalMotion.OMEGA_EARTH])

atmoMsg = messaging.AtmoPropsMsg()
atmoMsg.write(messaging.AtmoPropsMsgPayload(neutralDensity=density))

dragGeometryMsg = messaging.DragGeometryMsg()
dragGeometryMsg.write(messaging.DragGeometryMsgPayload(
projectedArea=area,
dragCoeff=cd,
r_CP_S=r_CP_S
))

siteFrameMsg = messaging.SCStatesMsg()
siteFrameMsg.write(messaging.SCStatesMsgPayload(
sigma_BN=sigma_SN,
v_BN_N=v_SN_N.tolist(),
r_BN_N=r_SN_N.tolist()
))

drag = cannonballDrag.CannonballDrag()
drag.dragGeometryInMsg.subscribeTo(dragGeometryMsg)
drag.atmoDensInMsg.subscribeTo(atmoMsg)
drag.referenceFrameStateInMsg.subscribeTo(siteFrameMsg)
drag.setUseAtmosphereRelativeVelocity(useRelVel)
if useRelVel:
drag.setPlanetOmega_N(omega_planet)
scSim.AddModelToTask("test", drag)

scSim.InitializeSimulation()
scSim.ConfigureStopTime(macros.sec2nano(dt))
scSim.ExecuteSimulation()

force_S = np.array(drag.forceOutMsg.read().force_S)
torque_S = np.array(drag.torqueOutMsg.read().torque_S)

# Expected
if useRelVel:
v_eff_N = v_SN_N - np.cross(omega_planet, r_SN_N)
else:
v_eff_N = v_SN_N

C_BN = np.array(rbk.MRP2C(sigma_SN))
v_eff_S = C_BN.dot(v_eff_N)
v_mag = np.linalg.norm(v_eff_N)
if v_mag <= 1e-12:
F_exp_S = np.zeros(3)
T_exp_S = np.zeros(3)
else:
F_mag = 0.5 * density * v_mag**2 * cd * area
v_hat_S = v_eff_S / np.linalg.norm(v_eff_S)
F_exp_S = -F_mag * v_hat_S
T_exp_S = np.cross(r_CP_S, F_exp_S)

return force_S, torque_S, F_exp_S, T_exp_S


def test_cannonballDragAtmoRelVelDisabled():
"""
Verify that when ``useAtmosphereRelativeVelocity`` is False (default), the module
computes drag using the inertial velocity and the result matches the analytical
cannonball drag formula.
"""
force_S, torque_S, F_exp_S, T_exp_S = _runCannonballDragAtmoRelVel(False)
npt.assert_allclose(force_S, F_exp_S, rtol=1e-14, atol=1e-10)
npt.assert_allclose(torque_S, T_exp_S, rtol=1e-14, atol=1e-10)


def test_cannonballDragAtmoRelVelEnabled():
"""
Verify that when ``useAtmosphereRelativeVelocity`` is True, the module subtracts
the planetary rotation contribution ``omega x r`` from the inertial velocity before
computing drag, and the result matches the analytical atmosphere-relative drag formula.
"""
force_S, torque_S, F_exp_S, T_exp_S = _runCannonballDragAtmoRelVel(True)
npt.assert_allclose(force_S, F_exp_S, rtol=1e-14, atol=1e-10)
npt.assert_allclose(torque_S, T_exp_S, rtol=1e-14, atol=1e-10)


@pytest.mark.skipif(not couldImportMujoco, reason="Compiled Basilisk without --mujoco")
@pytest.mark.parametrize("useRelVel", [False, True])
@pytest.mark.parametrize("orbitCase", ["LPO", "LTO"])
@pytest.mark.parametrize("planetCase", ["earth", "mars"])
def test_orbit(orbitCase: Literal["LPO", "LTO"], planetCase: Literal["earth", "mars"], showPlots = False):
def test_orbit(orbitCase: Literal["LPO", "LTO"], planetCase: Literal["earth", "mars"],
useRelVel: bool, showPlots = False):
"""
Integration test for ``CannonballDrag`` in an orbital simulation.

Expand All @@ -152,12 +249,17 @@ def test_orbit(orbitCase: Literal["LPO", "LTO"], planetCase: Literal["earth", "m
density, and drag force history when ``showPlots`` is enabled.
"""

def cannonballDragBFrame(dragCoeff, density, area, velInertial, sigmaBN):
speed = np.linalg.norm(velInertial)
def cannonballDragBFrame(dragCoeff, density, area, velInertial, sigmaBN,
posInertial=None, omegaPlanet=None):
if useRelVel and posInertial is not None and omegaPlanet is not None:
velEff = velInertial - np.cross(omegaPlanet, posInertial)
else:
velEff = velInertial
speed = np.linalg.norm(velEff)
if speed <= 0.0:
return np.zeros(3)

dragDirInertial = -velInertial / speed
dragDirInertial = -velEff / speed
dcmBN = rbk.MRP2C(sigmaBN)
dragDirBody = dcmBN.dot(dragDirInertial)

Expand Down Expand Up @@ -232,8 +334,13 @@ def cannonballDragBFrame(dragCoeff, density, area, velInertial, sigmaBN):
)
)

omegaPlanet = np.array([0.0, 0.0, 7.292115e-5]) # Earth rotation rate [rad/s]

dragModel = cannonballDrag.CannonballDrag()
dragModel.ModelTag = "drag"
dragModel.setUseAtmosphereRelativeVelocity(useRelVel)
if useRelVel:
dragModel.setPlanetOmega_N(omegaPlanet)
scene.AddModelToDynamicsTask(dragModel)
forceTorqueDrag: mujoco.MJForceTorqueActuator = dragModel.applyTo(mjBody)
dragModel.atmoDensInMsg.subscribeTo(atmoModel.envOutMsgs[0])
Expand Down Expand Up @@ -294,6 +401,8 @@ def cannonballDragBFrame(dragCoeff, density, area, velInertial, sigmaBN):
area=projectedArea,
velInertial=velocityData[timeIndex, :],
sigmaBN=attitudeData[timeIndex, :],
posInertial=positionData[timeIndex, :],
omegaPlanet=omegaPlanet,
)

npt.assert_allclose(
Expand Down
48 changes: 45 additions & 3 deletions src/simulation/forceTorque/cannonballDrag/cannonballDrag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
*/
#include "cannonballDrag.h"

#include <Eigen/Dense>
#include "architecture/utilities/avsEigenMRP.h"

void
Expand All @@ -44,8 +43,13 @@ CannonballDrag::UpdateState(uint64_t CurrentSimNanos)
sigma_SN = Eigen::Map<const Eigen::Vector3d>(siteStatePayload.sigma_BN);
const Eigen::Matrix3d dcm_SN = sigma_SN.toRotationMatrix().transpose();

// inertial velocity of the center of the S frame, expressed in the S frame
const auto v_S = dcm_SN*Eigen::Map<const Eigen::Vector3d>(siteStatePayload.v_BN_N);
// velocity used for drag: inertial or atmosphere-relative
Eigen::Vector3d vRel_N = Eigen::Map<const Eigen::Vector3d>(siteStatePayload.v_BN_N);
if (this->useAtmosphereRelativeVelocity) {
const Eigen::Map<const Eigen::Vector3d> r_N(siteStatePayload.r_BN_N);
vRel_N -= this->planetOmega_N.cross(r_N);
}
const auto v_S = dcm_SN * vRel_N;
const auto v = v_S.norm();

const Eigen::Vector3d force_S = -0.5 * cd * area * v * density * v_S;
Expand All @@ -63,6 +67,44 @@ CannonballDrag::UpdateState(uint64_t CurrentSimNanos)
TorqueAtSiteMsg_C_write(&torquePayload, &this->torqueOutMsgC, this->moduleID, CurrentSimNanos);
}

/*!
* @brief Enables or disables the use of atmosphere-relative velocity for drag computation.
* When enabled, the drag force is computed using v_rel = v_sc - (omega_planet x r_sc).
* @param useRelVel true to use atmosphere-relative velocity, false to use inertial velocity
*/
void CannonballDrag::setUseAtmosphereRelativeVelocity(bool useRelVel)
{
this->useAtmosphereRelativeVelocity = useRelVel;
}

/*!
* @brief Returns whether atmosphere-relative velocity is used in drag computation.
* @return true if atmosphere-relative velocity is enabled
*/
bool CannonballDrag::getUseAtmosphereRelativeVelocity() const
{
return this->useAtmosphereRelativeVelocity;
}

/*!
* @brief Sets the planetary rotation vector expressed in the inertial frame.
* Used to compute the atmosphere velocity when useAtmosphereRelativeVelocity is enabled.
* For Earth, the default is taken from OMEGA_EARTH in astroConstants.h: [0, 0, 7.2921159e-5] rad/s.
* @param omega Planetary rotation vector [rad/s] in inertial frame N
*/
void CannonballDrag::setPlanetOmega_N(const Eigen::Vector3d& omega)
{
this->planetOmega_N = omega;
}

/*!
* @brief Returns the planetary rotation vector expressed in the inertial frame.
* @return omega_planet [rad/s] in inertial frame N
*/
Eigen::Vector3d CannonballDrag::getPlanetOmega_N() const
{
return this->planetOmega_N;
}

void CannonballDrag::Reset(uint64_t /*CurrentSimNanos*/)
{
Expand Down
18 changes: 18 additions & 0 deletions src/simulation/forceTorque/cannonballDrag/cannonballDrag.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,9 @@
#ifndef AERODYNAMIC_DRAG_H
#define AERODYNAMIC_DRAG_H

#include <Eigen/Dense>
#include "architecture/utilities/bskLogging.h"
#include "architecture/utilities/astroConstants.h"
#include "architecture/messaging/messaging.h"
#include "architecture/_GeneralModuleFiles/sys_model.h"

Expand Down Expand Up @@ -94,6 +96,22 @@ class CannonballDrag : public SysModel

/** @brief Logger */
BSKLogger bskLogger;

/** @brief Enable or disable atmosphere-relative velocity for drag computation. */
void setUseAtmosphereRelativeVelocity(bool useRelVel);
/** @brief Returns whether atmosphere-relative velocity is enabled. */
bool getUseAtmosphereRelativeVelocity() const;
/**
* @brief Set the planetary rotation vector in the inertial frame [rad/s].
* Defaults to Earth's rotation rate. Used when useAtmosphereRelativeVelocity is enabled.
*/
void setPlanetOmega_N(const Eigen::Vector3d& omega);
/** @brief Returns the planetary rotation vector in the inertial frame [rad/s]. */
Eigen::Vector3d getPlanetOmega_N() const;

private:
bool useAtmosphereRelativeVelocity = false;
Eigen::Vector3d planetOmega_N{0.0, 0.0, OMEGA_EARTH};
};


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
%}
%include "std_string.i"
%include "swig_conly_data.i"
%include "swig_eigen.i"

// We add these helper functions on the Python side so that the module
// itself doesn't depend on any MuJoCo imports.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,13 @@ This module evaluates aerodynamic drag with force magnitude computed as

where :math:`\rho` is the local neutral atmospheric density, :math:`v` is the magnitude of the relative flow velocity at the site, :math:`C_D` is the drag coefficient, and :math:`A` is the projected area. The drag force direction is opposite the relative velocity vector.

By default, drag is computed using the inertial velocity :math:`\mathbf{v}_{SN}`. When the optional atmosphere-relative velocity mode is enabled via ``setUseAtmosphereRelativeVelocity(True)``, the module instead uses

.. math::
\mathbf{v}_\text{rel} = \mathbf{v}_{SN} - \boldsymbol{\omega}_\text{planet} \times \mathbf{r}_{SN}

where :math:`\boldsymbol{\omega}_\text{planet}` is the planetary rotation vector expressed in the inertial frame (defaults to Earth's rotation rate along the inertial :math:`\hat{z}` axis). This vector can be overridden via ``setPlanetOmega_N()``.

The force is applied at a specified center-of-pressure location relative to the site frame origin, producing a torque given by

.. math::
Expand Down Expand Up @@ -62,7 +69,7 @@ At each update step, the module performs the following operations:
1. Reads the atmospheric density from ``atmoDensInMsg``.
2. Reads the drag coefficient, projected area, and center-of-pressure location from ``dragGeometryInMsg``.
3. Reads the site frame attitude and inertial velocity from ``referenceFrameStateInMsg``.
4. Transforms the inertial velocity into the site frame using the provided attitude.
4. Computes the velocity used for drag: if atmosphere-relative mode is enabled, subtracts :math:`\boldsymbol{\omega}_\text{planet} \times \mathbf{r}_{SN}` from the inertial velocity; otherwise uses the inertial velocity directly. Transforms the result into the site frame.
5. Computes the drag force magnitude and direction in the site frame.
6. Computes the resulting torque about the site frame origin.
7. Publishes the force and torque through ``forceOutMsg`` and ``torqueOutMsg`` (and ``forceOutMsgC`` and ``torqueOutMsgC``).
Expand Down
Loading