Struct re_types::archetypes::Pinhole

source ·
pub struct Pinhole {
    pub image_from_camera: PinholeProjection,
    pub resolution: Option<Resolution>,
    pub camera_xyz: Option<ViewCoordinates>,
}
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::try_from(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),
    )?;

    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)]),
    )?;

    Ok(())
}

Fields§

§image_from_camera: PinholeProjection

Camera projection, from image coordinates to view coordinates.

§resolution: Option<Resolution>

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<ViewCoordinates>

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.

Implementations§

source§

impl Pinhole

source

pub const NUM_COMPONENTS: usize = 4usize

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

source§

impl Pinhole

source

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

Create a new Pinhole.

source

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

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_camera_xyz(self, camera_xyz: impl Into<ViewCoordinates>) -> Self

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§

impl Pinhole

source

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

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) -> Self

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 fov_y(&self) -> Option<f32>

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

source

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

Width/height ratio of the camera sensor.

source

pub fn focal_length_in_pixels(&self) -> Vec2D

X & Y focal length in pixels.

see definition of intrinsic matrix

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 indicator() -> MaybeOwnedComponentBatch<'static>

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

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

Returns the names of all components that must be provided by the user when constructing this archetype.
source§

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

Returns the names of all components that should be provided by the user when constructing this archetype.
source§

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

Returns the names of all components that may be provided by the user when constructing this archetype.
source§

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

Returns the names of all components 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 = (ComponentName, Box<dyn Array>)> ) -> DeserializationResult<Self>

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, Box<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_component_batches(&self) -> Vec<MaybeOwnedComponentBatch<'_>>

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

fn to_arrow(&self) -> Result<Vec<(Field, Box<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

Formats the value using the given formatter. 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 the total size of self on the heap, in bytes.
source§

fn is_pod() -> bool

Is Self just plain old data? 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§

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> 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<T> DynClone for T
where T: Clone,

source§

fn __clone_box(&self, _: Private) -> *mut ()

source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

source§

impl<T> Instrument for T

source§

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

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

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> 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
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> WithSubscriber for T

source§

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
source§

fn with_current_subscriber(self) -> WithDispatch<Self>

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