Struct nyx_space::dynamics::spacecraft::Spacecraft [−][src]
Fields
orbital_dyn: Arc<OrbitalDynamics<'a>>
force_models: Vec<Arc<dyn ForceModel + 'a>>
ctrl: Option<Arc<dyn ThrustControl + 'a>>
decrement_mass: bool
Implementations
impl<'a> Spacecraft<'a>
[src]
pub fn with_ctrl(
orbital_dyn: Arc<OrbitalDynamics<'a>>,
ctrl: Arc<dyn ThrustControl + 'a>
) -> Arc<Self>
[src]
orbital_dyn: Arc<OrbitalDynamics<'a>>,
ctrl: Arc<dyn ThrustControl + 'a>
) -> Arc<Self>
Initialize a Spacecraft with a set of orbital dynamics and a propulsion subsystem. By default, the mass of the vehicle will be decremented as propellant is consummed.
pub fn with_ctrl_no_decr(
orbital_dyn: Arc<OrbitalDynamics<'a>>,
ctrl: Arc<dyn ThrustControl + 'a>
) -> Arc<Self>
[src]
orbital_dyn: Arc<OrbitalDynamics<'a>>,
ctrl: Arc<dyn ThrustControl + 'a>
) -> Arc<Self>
Initialize a Spacecraft with a set of orbital dynamics and a propulsion subsystem. Will not decrement the fuel mass as propellant is consummed.
pub fn new(orbital_dyn: Arc<OrbitalDynamics<'a>>) -> Arc<Self>
[src]
Initialize a Spacecraft with a set of orbital dynamics and with SRP enabled.
pub fn new_raw(orbital_dyn: Arc<OrbitalDynamics<'a>>) -> Self
[src]
Initialize a Spacecraft with a set of orbital dynamics and with SRP enabled.
pub fn with_model(
orbital_dyn: Arc<OrbitalDynamics<'a>>,
force_model: Arc<dyn ForceModel + 'a>
) -> Arc<Self>
[src]
orbital_dyn: Arc<OrbitalDynamics<'a>>,
force_model: Arc<dyn ForceModel + 'a>
) -> Arc<Self>
Initialize new spacecraft dynamics with the provided orbital mechanics and with the provided force model.
pub fn with_models(
orbital_dyn: Arc<OrbitalDynamics<'a>>,
force_models: Vec<Arc<dyn ForceModel + 'a>>
) -> Arc<Self>
[src]
orbital_dyn: Arc<OrbitalDynamics<'a>>,
force_models: Vec<Arc<dyn ForceModel + 'a>>
) -> Arc<Self>
Initialize new spacecraft dynamics with a vector of force models.
pub fn add_model(&mut self, force_model: Arc<dyn ForceModel + 'a>)
[src]
pub fn ctrl_achieved(&self, state: &SpacecraftState) -> Result<bool, NyxError>
[src]
A shortcut to spacecraft.ctrl if the control is defined
Trait Implementations
impl<'a> Clone for Spacecraft<'a>
[src]
fn clone(&self) -> Spacecraft<'a>
[src]
pub fn clone_from(&mut self, source: &Self)
1.0.0[src]
impl<'a> Dynamics for Spacecraft<'a>
[src]
type HyperdualSize = U7
The state of the associated hyperdual state, almost always StateType + U1
type StateType = SpacecraftState
fn finally(
&self,
next_state: Self::StateType
) -> Result<Self::StateType, NyxError>
[src]
&self,
next_state: Self::StateType
) -> Result<Self::StateType, NyxError>
fn eom(
&self,
delta_t: f64,
state: &VectorN<f64, U43>,
ctx: &SpacecraftState
) -> Result<VectorN<f64, U43>, NyxError>
[src]
&self,
delta_t: f64,
state: &VectorN<f64, U43>,
ctx: &SpacecraftState
) -> Result<VectorN<f64, U43>, NyxError>
fn dual_eom(
&self,
delta_t_s: f64,
state_vec: &VectorN<Hyperdual<f64, Self::HyperdualSize>, U7>,
ctx: &Self::StateType
) -> Result<(VectorN<f64, U7>, MatrixN<f64, U7>), NyxError>
[src]
&self,
delta_t_s: f64,
state_vec: &VectorN<Hyperdual<f64, Self::HyperdualSize>, U7>,
ctx: &Self::StateType
) -> Result<(VectorN<f64, U7>, MatrixN<f64, U7>), NyxError>
fn eom_grad(
&self,
delta_t_s: f64,
state_vec: &VectorN<f64, <Self::StateType as State>::Size>,
state_ctx: &Self::StateType
) -> Result<(VectorN<f64, <Self::StateType as State>::Size>, MatrixN<f64, <Self::StateType as State>::Size>), NyxError> where
DefaultAllocator: Allocator<f64, <Self::StateType as State>::Size> + Allocator<f64, <Self::StateType as State>::Size, <Self::StateType as State>::Size> + Allocator<f64, Self::HyperdualSize> + Allocator<Hyperdual<f64, Self::HyperdualSize>, <Self::StateType as State>::Size>,
Owned<f64, Self::HyperdualSize>: Copy,
[src]
&self,
delta_t_s: f64,
state_vec: &VectorN<f64, <Self::StateType as State>::Size>,
state_ctx: &Self::StateType
) -> Result<(VectorN<f64, <Self::StateType as State>::Size>, MatrixN<f64, <Self::StateType as State>::Size>), NyxError> where
DefaultAllocator: Allocator<f64, <Self::StateType as State>::Size> + Allocator<f64, <Self::StateType as State>::Size, <Self::StateType as State>::Size> + Allocator<f64, Self::HyperdualSize> + Allocator<Hyperdual<f64, Self::HyperdualSize>, <Self::StateType as State>::Size>,
Owned<f64, Self::HyperdualSize>: Copy,
Auto Trait Implementations
impl<'a> !RefUnwindSafe for Spacecraft<'a>
impl<'a> Send for Spacecraft<'a>
impl<'a> Sync for Spacecraft<'a>
impl<'a> Unpin for Spacecraft<'a>
impl<'a> !UnwindSafe for Spacecraft<'a>
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
pub fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Pointable for T
pub const ALIGN: usize
type Init = T
The type for initializers.
pub unsafe fn init(init: <T as Pointable>::Init) -> usize
pub unsafe fn deref<'a>(ptr: usize) -> &'a T
pub unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T
pub unsafe fn drop(ptr: usize)
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn is_in_subset(&self) -> bool
pub fn to_subset_unchecked(&self) -> SS
pub fn from_subset(element: &SS) -> SP
impl<T> ToOwned for T where
T: Clone,
[src]
T: Clone,
type Owned = T
The resulting type after obtaining ownership.
pub fn to_owned(&self) -> T
[src]
pub fn clone_into(&self, target: &mut T)
[src]
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
pub fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
pub fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
V: MultiLane<T>,