Struct rerun::sdk::archetypes::Pinhole

source ·
pub struct Pinhole {
    pub image_from_camera: Option<SerializedComponentBatch>,
    pub resolution: Option<SerializedComponentBatch>,
    pub camera_xyz: Option<SerializedComponentBatch>,
    pub image_plane_distance: Option<SerializedComponentBatch>,
}
Expand description

Archetype: Camera perspective projection (a.k.a. intrinsics).

§Examples

§Simple pinhole camera

use ndarray::{Array, ShapeBuilder};

fn main() -> Result<(), Box<dyn std::error::Error>> {
    let rec = rerun::RecordingStreamBuilder::new("rerun_example_pinhole").spawn()?;

    let mut image = Array::<u8, _>::default((3, 3, 3).f());
    image.map_inplace(|x| *x = rand::random());

    rec.log(
        "world/image",
        &rerun::Pinhole::from_focal_length_and_resolution([3., 3.], [3., 3.]),
    )?;
    rec.log(
        "world/image",
        &rerun::Image::from_color_model_and_tensor(rerun::ColorModel::RGB, image)?,
    )?;

    Ok(())
}

§Perspective pinhole camera

fn main() -> Result<(), Box<dyn std::error::Error>> {
    let rec = rerun::RecordingStreamBuilder::new("rerun_example_pinhole_perspective").spawn()?;

    let fov_y = std::f32::consts::FRAC_PI_4;
    let aspect_ratio = 1.7777778;
    rec.log(
        "world/cam",
        &rerun::Pinhole::from_fov_and_aspect_ratio(fov_y, aspect_ratio)
            .with_camera_xyz(rerun::components::ViewCoordinates::RUB)
            .with_image_plane_distance(0.1),
    )?;

    rec.log(
        "world/points",
        &rerun::Points3D::new([(0.0, 0.0, -0.5), (0.1, 0.1, -0.5), (-0.1, -0.1, -0.5)])
            .with_radii([0.025]),
    )?;

    Ok(())
}

Fields§

§image_from_camera: Option<SerializedComponentBatch>

Camera projection, from image coordinates to view coordinates.

§resolution: Option<SerializedComponentBatch>

Pixel resolution (usually integers) of child image space. Width and height.

Example:

[1920.0, 1440.0]

image_from_camera project onto the space spanned by (0,0) and resolution - 1.

§camera_xyz: Option<SerializedComponentBatch>

Sets the view coordinates for the camera.

All common values are available as constants on the components::ViewCoordinates class.

The default is ViewCoordinates::RDF, i.e. X=Right, Y=Down, Z=Forward, and this is also the recommended setting. This means that the camera frustum will point along the positive Z axis of the parent space, and the cameras “up” direction will be along the negative Y axis of the parent space.

The camera frustum will point whichever axis is set to F (or the opposite of B). When logging a depth image under this entity, this is the direction the point cloud will be projected. With RDF, the default forward is +Z.

The frustum’s “up” direction will be whichever axis is set to U (or the opposite of D). This will match the negative Y direction of pixel space (all images are assumed to have xyz=RDF). With RDF, the default is up is -Y.

The frustum’s “right” direction will be whichever axis is set to R (or the opposite of L). This will match the positive X direction of pixel space (all images are assumed to have xyz=RDF). With RDF, the default right is +x.

Other common formats are RUB (X=Right, Y=Up, Z=Back) and FLU (X=Forward, Y=Left, Z=Up).

NOTE: setting this to something else than RDF (the default) will change the orientation of the camera frustum, and make the pinhole matrix not match up with the coordinate system of the pinhole entity.

The pinhole matrix (the image_from_camera argument) always project along the third (Z) axis, but will be re-oriented to project along the forward axis of the camera_xyz argument.

§image_plane_distance: Option<SerializedComponentBatch>

The distance from the camera origin to the image plane when the projection is shown in a 3D viewer.

This is only used for visualization purposes, and does not affect the projection itself.

Implementations§

source§

impl Pinhole

source§

impl Pinhole

source

pub const NUM_COMPONENTS: usize = 5usize

The total number of components in the archetype: 1 required, 2 recommended, 2 optional

source§

impl Pinhole

source

pub fn new(image_from_camera: impl Into<PinholeProjection>) -> Pinhole

Create a new Pinhole.

source

pub fn update_fields() -> Pinhole

Update only some specific fields of a Pinhole.

source

pub fn clear_fields() -> Pinhole

Clear all the fields of a Pinhole.

source

pub fn columns<I>( self, _lengths: I, ) -> Result<impl Iterator<Item = SerializedComponentColumn>, SerializationError>
where I: IntoIterator<Item = usize> + Clone,

Partitions the component data into multiple sub-batches.

Specifically, this transforms the existing SerializedComponentBatches data into SerializedComponentColumns instead, via SerializedComponentBatch::partitioned.

This makes it possible to use RecordingStream::send_columns to send columnar data directly into Rerun.

The specified lengths must sum to the total length of the component batch.

source

pub fn columns_of_unit_batches( self, ) -> Result<impl Iterator<Item = SerializedComponentColumn>, SerializationError>

Helper to partition the component data into unit-length sub-batches.

This is semantically similar to calling Self::columns with std::iter::take(1).repeat(n), where n is automatically guessed.

source

pub fn with_image_from_camera( self, image_from_camera: impl Into<PinholeProjection>, ) -> Pinhole

Camera projection, from image coordinates to view coordinates.

source

pub fn with_many_image_from_camera( self, image_from_camera: impl IntoIterator<Item = impl Into<PinholeProjection>>, ) -> Pinhole

This method makes it possible to pack multiple crate::components::PinholeProjection in a single component batch.

This only makes sense when used in conjunction with Self::columns. Self::with_image_from_camera should be used when logging a single row’s worth of data.

source

pub fn with_resolution(self, resolution: impl Into<Resolution>) -> Pinhole

Pixel resolution (usually integers) of child image space. Width and height.

Example:

[1920.0, 1440.0]

image_from_camera project onto the space spanned by (0,0) and resolution - 1.

source

pub fn with_many_resolution( self, resolution: impl IntoIterator<Item = impl Into<Resolution>>, ) -> Pinhole

This method makes it possible to pack multiple crate::components::Resolution in a single component batch.

This only makes sense when used in conjunction with Self::columns. Self::with_resolution should be used when logging a single row’s worth of data.

source

pub fn with_camera_xyz(self, camera_xyz: impl Into<ViewCoordinates>) -> Pinhole

Sets the view coordinates for the camera.

All common values are available as constants on the components::ViewCoordinates class.

The default is ViewCoordinates::RDF, i.e. X=Right, Y=Down, Z=Forward, and this is also the recommended setting. This means that the camera frustum will point along the positive Z axis of the parent space, and the cameras “up” direction will be along the negative Y axis of the parent space.

The camera frustum will point whichever axis is set to F (or the opposite of B). When logging a depth image under this entity, this is the direction the point cloud will be projected. With RDF, the default forward is +Z.

The frustum’s “up” direction will be whichever axis is set to U (or the opposite of D). This will match the negative Y direction of pixel space (all images are assumed to have xyz=RDF). With RDF, the default is up is -Y.

The frustum’s “right” direction will be whichever axis is set to R (or the opposite of L). This will match the positive X direction of pixel space (all images are assumed to have xyz=RDF). With RDF, the default right is +x.

Other common formats are RUB (X=Right, Y=Up, Z=Back) and FLU (X=Forward, Y=Left, Z=Up).

NOTE: setting this to something else than RDF (the default) will change the orientation of the camera frustum, and make the pinhole matrix not match up with the coordinate system of the pinhole entity.

The pinhole matrix (the image_from_camera argument) always project along the third (Z) axis, but will be re-oriented to project along the forward axis of the camera_xyz argument.

source

pub fn with_many_camera_xyz( self, camera_xyz: impl IntoIterator<Item = impl Into<ViewCoordinates>>, ) -> Pinhole

This method makes it possible to pack multiple crate::components::ViewCoordinates in a single component batch.

This only makes sense when used in conjunction with Self::columns. Self::with_camera_xyz should be used when logging a single row’s worth of data.

source

pub fn with_image_plane_distance( self, image_plane_distance: impl Into<ImagePlaneDistance>, ) -> Pinhole

The distance from the camera origin to the image plane when the projection is shown in a 3D viewer.

This is only used for visualization purposes, and does not affect the projection itself.

source

pub fn with_many_image_plane_distance( self, image_plane_distance: impl IntoIterator<Item = impl Into<ImagePlaneDistance>>, ) -> Pinhole

This method makes it possible to pack multiple crate::components::ImagePlaneDistance in a single component batch.

This only makes sense when used in conjunction with Self::columns. Self::with_image_plane_distance should be used when logging a single row’s worth of data.

source§

impl Pinhole

source

pub const DEFAULT_CAMERA_XYZ: ViewCoordinates = ViewCoordinates::RDF

Camera orientation used when there’s no camera orientation explicitly logged.

  • x pointing right
  • y pointing down
  • z pointing into the image plane (this is convenient for reading out a depth image which has typically positive z values)
source

pub fn from_focal_length_and_resolution( focal_length: impl Into<Vec2D>, resolution: impl Into<Vec2D>, ) -> Pinhole

Creates a pinhole from the camera focal length and resolution, both specified in pixels.

The focal length is the diagonal of the projection matrix. Set the same value for x & y value for symmetric cameras, or two values for anamorphic cameras.

Assumes the principal point to be in the middle of the sensor.

source

pub fn from_fov_and_aspect_ratio(fov_y: f32, aspect_ratio: f32) -> Pinhole

Creates a pinhole from the camera vertical field of view (in radians) and aspect ratio (width/height).

Assumes the principal point to be in the middle of the sensor.

source

pub fn with_principal_point(self, principal_point: impl Into<Vec2D>) -> Pinhole

Principal point of the pinhole camera, i.e. the intersection of the optical axis and the image plane.

see definition of intrinsic matrix

This method can be relatively costly since it has to deserialize & reserialize the [`PinholeProjection`] component from/to its arrow representation. On performance critical paths, prefer first setting up the [`PinholeProjection`] component fully before passing it to the archetype.
source

pub fn fov_y(&self) -> Option<f32>

👎Deprecated since 0.22.0: Use Pinhole::image_from_camera_from_arrow & Pinhole::resolution_from_arrow to deserialize the components back, or better use the components prior to passing it to the archetype, and then call PinholeProjection::fov_y

Field of View on the Y axis, i.e. the angle between top and bottom (in radians).

Only returns a result if both projection & resolution are set.

source

pub fn resolution(&self) -> Option<Vec2>

👎Deprecated since 0.22.0: Use Pinhole::resolution_from_arrow to deserialize back to a Resolution component, or better use the Resolution prior to passing it to the archetype, and then use Resolution::into for the conversion

The resolution of the camera sensor in pixels.

source

pub fn aspect_ratio(&self) -> Option<f32>

👎Deprecated since 0.22.0: Use Pinhole::resolution_from_arrow to deserialize back to a Resolution component, or better use the Resolution prior to passing it to the archetype, and then use Resolution::aspect_ratio

Width/height ratio of the camera sensor.

source

pub fn image_from_camera_from_arrow( &self, ) -> Result<PinholeProjection, DeserializationError>

Deserializes the pinhole projection from the image_from_camera field.

Returns re_types_core::DeserializationError::MissingData if the component is not present.

source

pub fn resolution_from_arrow(&self) -> Result<Resolution, DeserializationError>

Deserializes the resolution from the resolution field.

Returns re_types_core::DeserializationError::MissingData if the component is not present.

source

pub fn focal_length_in_pixels(&self) -> Vec2D

👎Deprecated since 0.22.0: Use Pinhole::image_from_camera_from_arrow instead to deserialize back to a PinholeProjection component, or better use the PinholeProjection component prior to passing it to the archetype, and then call PinholeProjection::focal_length_in_pixels

X & Y focal length in pixels.

see definition of intrinsic matrix

source

pub fn principal_point(&self) -> Vec2

👎Deprecated since 0.22.0: Use Pinhole::image_from_camera_from_arrow instead to deserialize back to a PinholeProjection component, or better use the PinholeProjection component prior to passing it to the archetype, and then call PinholeProjection::principal_point

Principal point of the pinhole camera, i.e. the intersection of the optical axis and the image plane.

see definition of intrinsic matrix

source

pub fn project(&self, pixel: Vec3) -> Vec3

👎Deprecated since 0.22.0: Use Pinhole::image_from_camera_from_arrow instead to deserialize back to a PinholeProjection component, or better use the PinholeProjection component prior to passing it to the archetype, and then call PinholeProjection::project

Project camera-space coordinates into pixel coordinates, returning the same z/depth.

source

pub fn unproject(&self, pixel: Vec3) -> Vec3

👎Deprecated since 0.22.0: Use Pinhole::image_from_camera_from_arrow instead to deserialize back to a PinholeProjection component, or better use the PinholeProjection component prior to passing it to the archetype, and then call PinholeProjection::unproject

Given pixel coordinates and a world-space depth, return a position in the camera space.

The returned z is the same as the input z (depth).

Trait Implementations§

source§

impl Archetype for Pinhole

§

type Indicator = GenericIndicatorComponent<Pinhole>

The associated indicator component, whose presence indicates that the high-level archetype-based APIs were used to log the data. Read more
source§

fn name() -> ArchetypeName

The fully-qualified name of this archetype, e.g. rerun.archetypes.Points2D.
source§

fn display_name() -> &'static str

Readable name for displaying in UI.
source§

fn indicator() -> SerializedComponentBatch

Creates a ComponentBatch out of the associated Self::Indicator component. Read more
source§

fn required_components() -> Cow<'static, [ComponentDescriptor]>

Returns all component descriptors that must be provided by the user when constructing this archetype.
source§

fn recommended_components() -> Cow<'static, [ComponentDescriptor]>

Returns all component descriptors that should be provided by the user when constructing this archetype.
source§

fn optional_components() -> Cow<'static, [ComponentDescriptor]>

Returns all component descriptors that may be provided by the user when constructing this archetype.
source§

fn all_components() -> Cow<'static, [ComponentDescriptor]>

Returns all component descriptors that must, should and may be provided by the user when constructing this archetype. Read more
source§

fn from_arrow_components( arrow_data: impl IntoIterator<Item = (ComponentDescriptor, Arc<dyn Array>)>, ) -> Result<Pinhole, DeserializationError>

Given an iterator of Arrow arrays and their respective ComponentNames, deserializes them into this archetype. Read more
source§

fn from_arrow( data: impl IntoIterator<Item = (Field, Arc<dyn Array>)>, ) -> Result<Self, DeserializationError>
where Self: Sized,

Given an iterator of Arrow arrays and their respective field metadata, deserializes them into this archetype. Read more
source§

impl AsComponents for Pinhole

source§

fn as_serialized_batches(&self) -> Vec<SerializedComponentBatch>

Exposes the object’s contents as a set of SerializedComponentBatches. Read more
source§

fn to_arrow(&self) -> Result<Vec<(Field, Arc<dyn Array>)>, SerializationError>

Serializes all non-null Components of this bundle into Arrow arrays. Read more
source§

impl Clone for Pinhole

source§

fn clone(&self) -> Pinhole

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl Debug for Pinhole

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result<(), Error>

Formats the value using the given formatter. Read more
source§

impl Default for Pinhole

source§

fn default() -> Pinhole

Returns the “default value” for a type. Read more
source§

impl PartialEq for Pinhole

source§

fn eq(&self, other: &Pinhole) -> bool

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

fn ne(&self, other: &Rhs) -> bool

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl SizeBytes for Pinhole

source§

fn heap_size_bytes(&self) -> u64

Returns how many bytes self uses on the heap. Read more
source§

fn total_size_bytes(&self) -> u64

Returns the total size of self in bytes, accounting for both stack and heap space.
source§

fn stack_size_bytes(&self) -> u64

Returns the total size of self on the stack, in bytes. Read more
source§

fn is_pod() -> bool

Is Self just plain old data? Read more
source§

impl ArchetypeReflectionMarker for Pinhole

source§

impl StructuralPartialEq for Pinhole

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for T
where T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Az for T

source§

fn az<Dst>(self) -> Dst
where T: Cast<Dst>,

Casts the value.
source§

impl<T> Borrow<T> for T
where T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<Src, Dst> CastFrom<Src> for Dst
where Src: Cast<Dst>,

source§

fn cast_from(src: Src) -> Dst

Casts the value.
source§

impl<T> CheckedAs for T

source§

fn checked_as<Dst>(self) -> Option<Dst>
where T: CheckedCast<Dst>,

Casts the value.
source§

impl<Src, Dst> CheckedCastFrom<Src> for Dst
where Src: CheckedCast<Dst>,

source§

fn checked_cast_from(src: Src) -> Option<Dst>

Casts the value.
source§

impl<T> CloneToUninit for T
where T: Clone,

source§

default unsafe fn clone_to_uninit(&self, dst: *mut T)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dst. Read more
§

impl<T> Conv for T

§

fn conv<T>(self) -> T
where Self: Into<T>,

Converts self into T using Into<T>. Read more
§

impl<T> Downcast<T> for T

§

fn downcast(&self) -> &T

§

impl<T> Downcast for T
where T: Any,

§

fn into_any(self: Box<T>) -> Box<dyn Any>

Convert Box<dyn Trait> (where Trait: Downcast) to Box<dyn Any>. Box<dyn Any> can then be further downcast into Box<ConcreteType> where ConcreteType implements Trait.
§

fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>

Convert Rc<Trait> (where Trait: Downcast) to Rc<Any>. Rc<Any> can then be further downcast into Rc<ConcreteType> where ConcreteType implements Trait.
§

fn as_any(&self) -> &(dyn Any + 'static)

Convert &Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &Any’s vtable from &Trait’s.
§

fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)

Convert &mut Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &mut Any’s vtable from &mut Trait’s.
§

impl<T> DowncastSync for T
where T: Any + Send + Sync,

§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Send + Sync>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
source§

impl<T> DynClone for T
where T: Clone,

source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

§

impl<T> FromRef<T> for T
where T: Clone,

§

fn from_ref(input: &T) -> T

Converts to this type from a reference to the input type.
§

impl<T> Instrument for T

§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided [Span], returning an Instrumented wrapper. Read more
§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
source§

impl<T, U> Into<U> for T
where U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T> IntoEither for T

source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts self into a Left variant of Either<Self, Self> if into_left is true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts self into a Left variant of Either<Self, Self> if into_left(&self) returns true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
source§

impl<T> IntoRequest<T> for T

source§

fn into_request(self) -> Request<T>

Wrap the input message T in a tonic::Request
source§

impl<Src, Dst> LosslessTryInto<Dst> for Src
where Dst: LosslessTryFrom<Src>,

source§

fn lossless_try_into(self) -> Option<Dst>

Performs the conversion.
source§

impl<Src, Dst> LossyInto<Dst> for Src
where Dst: LossyFrom<Src>,

source§

fn lossy_into(self) -> Dst

Performs the conversion.
§

impl<T> NoneValue for T
where T: Default,

§

type NoneType = T

§

fn null_value() -> T

The none-equivalent value.
source§

impl<T> OverflowingAs for T

source§

fn overflowing_as<Dst>(self) -> (Dst, bool)
where T: OverflowingCast<Dst>,

Casts the value.
source§

impl<Src, Dst> OverflowingCastFrom<Src> for Dst
where Src: OverflowingCast<Dst>,

source§

fn overflowing_cast_from(src: Src) -> (Dst, bool)

Casts the value.
§

impl<T> Pipe for T
where T: ?Sized,

§

fn pipe<R>(self, func: impl FnOnce(Self) -> R) -> R
where Self: Sized,

Pipes by value. This is generally the method you want to use. Read more
§

fn pipe_ref<'a, R>(&'a self, func: impl FnOnce(&'a Self) -> R) -> R
where R: 'a,

Borrows self and passes that borrow into the pipe function. Read more
§

fn pipe_ref_mut<'a, R>(&'a mut self, func: impl FnOnce(&'a mut Self) -> R) -> R
where R: 'a,

Mutably borrows self and passes that borrow into the pipe function. Read more
§

fn pipe_borrow<'a, B, R>(&'a self, func: impl FnOnce(&'a B) -> R) -> R
where Self: Borrow<B>, B: 'a + ?Sized, R: 'a,

Borrows self, then passes self.borrow() into the pipe function. Read more
§

fn pipe_borrow_mut<'a, B, R>( &'a mut self, func: impl FnOnce(&'a mut B) -> R, ) -> R
where Self: BorrowMut<B>, B: 'a + ?Sized, R: 'a,

Mutably borrows self, then passes self.borrow_mut() into the pipe function. Read more
§

fn pipe_as_ref<'a, U, R>(&'a self, func: impl FnOnce(&'a U) -> R) -> R
where Self: AsRef<U>, U: 'a + ?Sized, R: 'a,

Borrows self, then passes self.as_ref() into the pipe function.
§

fn pipe_as_mut<'a, U, R>(&'a mut self, func: impl FnOnce(&'a mut U) -> R) -> R
where Self: AsMut<U>, U: 'a + ?Sized, R: 'a,

Mutably borrows self, then passes self.as_mut() into the pipe function.
§

fn pipe_deref<'a, T, R>(&'a self, func: impl FnOnce(&'a T) -> R) -> R
where Self: Deref<Target = T>, T: 'a + ?Sized, R: 'a,

Borrows self, then passes self.deref() into the pipe function.
§

fn pipe_deref_mut<'a, T, R>( &'a mut self, func: impl FnOnce(&'a mut T) -> R, ) -> R
where Self: DerefMut<Target = T> + Deref, T: 'a + ?Sized, R: 'a,

Mutably borrows self, then passes self.deref_mut() into the pipe function.
§

impl<T> Pointable for T

§

const ALIGN: usize = _

The alignment of pointer.
§

type Init = T

The type for initializers.
§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
source§

impl<T> Same for T

§

type Output = T

Should always be Self
source§

impl<T> SaturatingAs for T

source§

fn saturating_as<Dst>(self) -> Dst
where T: SaturatingCast<Dst>,

Casts the value.
source§

impl<Src, Dst> SaturatingCastFrom<Src> for Dst
where Src: SaturatingCast<Dst>,

source§

fn saturating_cast_from(src: Src) -> Dst

Casts the value.
§

impl<T> Tap for T

§

fn tap(self, func: impl FnOnce(&Self)) -> Self

Immutable access to a value. Read more
§

fn tap_mut(self, func: impl FnOnce(&mut Self)) -> Self

Mutable access to a value. Read more
§

fn tap_borrow<B>(self, func: impl FnOnce(&B)) -> Self
where Self: Borrow<B>, B: ?Sized,

Immutable access to the Borrow<B> of a value. Read more
§

fn tap_borrow_mut<B>(self, func: impl FnOnce(&mut B)) -> Self
where Self: BorrowMut<B>, B: ?Sized,

Mutable access to the BorrowMut<B> of a value. Read more
§

fn tap_ref<R>(self, func: impl FnOnce(&R)) -> Self
where Self: AsRef<R>, R: ?Sized,

Immutable access to the AsRef<R> view of a value. Read more
§

fn tap_ref_mut<R>(self, func: impl FnOnce(&mut R)) -> Self
where Self: AsMut<R>, R: ?Sized,

Mutable access to the AsMut<R> view of a value. Read more
§

fn tap_deref<T>(self, func: impl FnOnce(&T)) -> Self
where Self: Deref<Target = T>, T: ?Sized,

Immutable access to the Deref::Target of a value. Read more
§

fn tap_deref_mut<T>(self, func: impl FnOnce(&mut T)) -> Self
where Self: DerefMut<Target = T> + Deref, T: ?Sized,

Mutable access to the Deref::Target of a value. Read more
§

fn tap_dbg(self, func: impl FnOnce(&Self)) -> Self

Calls .tap() only in debug builds, and is erased in release builds.
§

fn tap_mut_dbg(self, func: impl FnOnce(&mut Self)) -> Self

Calls .tap_mut() only in debug builds, and is erased in release builds.
§

fn tap_borrow_dbg<B>(self, func: impl FnOnce(&B)) -> Self
where Self: Borrow<B>, B: ?Sized,

Calls .tap_borrow() only in debug builds, and is erased in release builds.
§

fn tap_borrow_mut_dbg<B>(self, func: impl FnOnce(&mut B)) -> Self
where Self: BorrowMut<B>, B: ?Sized,

Calls .tap_borrow_mut() only in debug builds, and is erased in release builds.
§

fn tap_ref_dbg<R>(self, func: impl FnOnce(&R)) -> Self
where Self: AsRef<R>, R: ?Sized,

Calls .tap_ref() only in debug builds, and is erased in release builds.
§

fn tap_ref_mut_dbg<R>(self, func: impl FnOnce(&mut R)) -> Self
where Self: AsMut<R>, R: ?Sized,

Calls .tap_ref_mut() only in debug builds, and is erased in release builds.
§

fn tap_deref_dbg<T>(self, func: impl FnOnce(&T)) -> Self
where Self: Deref<Target = T>, T: ?Sized,

Calls .tap_deref() only in debug builds, and is erased in release builds.
§

fn tap_deref_mut_dbg<T>(self, func: impl FnOnce(&mut T)) -> Self
where Self: DerefMut<Target = T> + Deref, T: ?Sized,

Calls .tap_deref_mut() only in debug builds, and is erased in release builds.
§

impl<T> To for T
where T: ?Sized,

§

fn to<T>(self) -> T
where Self: Into<T>,

Converts to T by calling Into<T>::into.
§

fn try_to<T>(self) -> Result<T, Self::Error>
where Self: TryInto<T>,

Tries to convert to T by calling TryInto<T>::try_into.
source§

impl<T> ToOwned for T
where T: Clone,

§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
§

impl<T> TryConv for T

§

fn try_conv<T>(self) -> Result<T, Self::Error>
where Self: TryInto<T>,

Attempts to convert self into T using TryInto<T>. Read more
source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
source§

impl<T> UnwrappedAs for T

source§

fn unwrapped_as<Dst>(self) -> Dst
where T: UnwrappedCast<Dst>,

Casts the value.
source§

impl<Src, Dst> UnwrappedCastFrom<Src> for Dst
where Src: UnwrappedCast<Dst>,

source§

fn unwrapped_cast_from(src: Src) -> Dst

Casts the value.
§

impl<T> Upcast<T> for T

§

fn upcast(&self) -> Option<&T>

§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

§

fn vzip(self) -> V

§

impl<T> WithSubscriber for T

§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a [WithDispatch] wrapper. Read more
§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a [WithDispatch] wrapper. Read more
source§

impl<T> WrappingAs for T

source§

fn wrapping_as<Dst>(self) -> Dst
where T: WrappingCast<Dst>,

Casts the value.
source§

impl<Src, Dst> WrappingCastFrom<Src> for Dst
where Src: WrappingCast<Dst>,

source§

fn wrapping_cast_from(src: Src) -> Dst

Casts the value.
§

impl<T> ErasedDestructor for T
where T: 'static,

§

impl<T> MaybeSendSync for T

§

impl<T> Ungil for T
where T: Send,

§

impl<T> WasmNotSend for T
where T: Send,

§

impl<T> WasmNotSendSync for T

§

impl<T> WasmNotSync for T
where T: Sync,