Struct CameraInfo

Source
#[repr(C)]
pub struct CameraInfo { pub header: Header, pub height: u32, pub width: u32, pub distortion_model: DistortionModel, pub d: Vec<f64>, pub k: [f64; 9], pub r: [f64; 9], pub p: [f64; 12], pub binning_x: u32, pub binning_y: u32, pub roi: RegionOfInterest, }
Expand description

§Header timestamp should be acquisition time of image

Header frame_id should be optical frame of camera origin of frame should be optical center of camera +x should point to the right in the image +y should point down in the image +z should point into the plane of the image

Fields§

§header: Header
§height: u32

Calibrated width

§width: u32

Calibrated height

§distortion_model: DistortionModel§d: Vec<f64>

distortion parameters

§k: [f64; 9]

Intrinsic camera matrix for the raw images. [ fx 0 cx ] [ 0 fy cy ] [ 0 0 1 ] Projectd 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths (fx,fy) and principal point (cx, cy)

§r: [f64; 9]

Rectification matrix for stereo cameras A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel

§p: [f64; 12]

§Projection/camera matrix

§binning_x: u32§binning_y: u32§roi: RegionOfInterest

Region of interest (subwindow of full camera resolution), given in full resolution (unbinned) image coordinates. A particular ROI always denotes the same window of pixels on the camera sensor, regardless of binning settings. The default setting of roi (all values 0) is considered the same as full resolution (roi.width = width, roi.height = height).

Implementations§

Source§

impl CameraInfo

Source

pub fn create_topic_with_name( participant: &DdsParticipant, name: &str, maybe_qos: Option<DdsQos>, maybe_listener: Option<DdsListener>, ) -> Result<DdsTopic<Self>, DDSError>

Create a topic using of this Type specifying the topic name

§Arguments
  • participant - The participant handle onto which this topic should be created
  • name - The name of the topic
  • maybe_qos - A QoS structure for this topic. The Qos is optional
  • maybe_listener - A listener to use on this topic. The listener is optional
Source

pub fn create_topic( participant: &DdsParticipant, maybe_topic_prefix: Option<&str>, maybe_qos: Option<DdsQos>, maybe_listener: Option<DdsListener>, ) -> Result<DdsTopic<Self>, DDSError>

Create a topic of this Type using the default topic name. The default topic name is provided by the Self::topic_name function.

§Arguments
  • participant - The participant handle onto which this topic should be created
  • maybe_topic_prefix - An additional prefix to be added to the topic name. This can be None
  • maybe_qos - A QoS structure for this topic. The Qos is optional
  • maybe_listener - A listener to use on this topic. The listener is optional
Source

pub fn create_sample_buffer(len: usize) -> SampleBuffer<CameraInfo>

Create a sample buffer for storing an array of samples You can pass the sample buffer into a read to read multiple samples. Multiple samples are useful when you have one or more keys in your topic structure. Each value of the key will result in the storage of another sample.

Trait Implementations§

Source§

impl<'de> Deserialize<'de> for CameraInfo

Source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Source§

impl Serialize for CameraInfo

Source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
Source§

impl TopicType for CameraInfo

Source§

fn key_cdr(&self) -> Vec<u8>

return the cdr encoding for the key. The encoded string includes the four byte encapsulation string.

Source§

fn is_fixed_size() -> bool

Source§

fn has_key() -> bool

Source§

fn force_md5_keyhash() -> bool

Source§

fn hash(&self, basehash: u32) -> u32

Source§

fn typename() -> CString

The type name for this topic
Source§

fn topic_name(maybe_prefix: Option<&str>) -> String

The default topic_name to use when creating a topic of this type. The default implementation uses ‘/’ instead of ‘::’ to form a unix like path. A prefix can optionally be added

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

Source§

fn from(t: T) -> T

Returns the argument unchanged.

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, U> TryFrom<U> for T
where U: Into<T>,

Source§

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

Source§

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> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,