supereight
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
se::PinholeCamera::Config Struct Reference

#include <pinhole_camera.hpp>

Inheritance diagram for se::PinholeCamera::Config:
Inheritance graph
[legend]
Collaboration diagram for se::PinholeCamera::Config:
Collaboration graph
[legend]

Public Member Functions

void readYaml (const std::string &filename)
 Reads the struct members from the "sensor" node of a YAML file.
 
Config operator/ (const float downsampling_factor) const
 
- Public Member Functions inherited from se::SensorBase< DerivedT >::Config
void readYaml (const std::string &filename)
 Reads the struct members from the "sensor" node of a YAML file.
 
Config operator/ (const float downsampling_factor) const
 

Public Attributes

float fx = std::numeric_limits<float>::quiet_NaN()
 The sensor's horizontal focal length in pixels.
 
float fy = std::numeric_limits<float>::quiet_NaN()
 The sensor's vertical focal length in pixels.
 
float cx = std::numeric_limits<float>::quiet_NaN()
 The sensor's optical centre horizontal coordinate in pixels.
 
float cy = std::numeric_limits<float>::quiet_NaN()
 The sensor's optical centre vertical coordinate in pixels.
 
- Public Attributes inherited from se::SensorBase< DerivedT >::Config
int width = 0
 The width of images produced by the sensor in pixels.
 
int height = 0
 The height of images produced by the sensor in pixels.
 
float near_plane = 0.01f
 The sensor's near plane in metres.
 
float far_plane = 10.0f
 The sensor's far plane in metres.
 
Eigen::Isometry3f T_BS = Eigen::Isometry3f::Identity()
 The transformation from the sensor frame S to the body frame B.
 
std::vector< floatpixel_voxel_ratio_per_scale = {1.5f, 3.0f, 6.0f}
 The pixel-size to voxel-size ratio thresholds, in ascendig order and in physical coordinates, for computing the integration scale.
 

Member Function Documentation

◆ readYaml()

void se::PinholeCamera::Config::readYaml ( const std::string &  filename)

Reads the struct members from the "sensor" node of a YAML file.

Members not present in the YAML file aren't modified.

◆ operator/()

Config se::PinholeCamera::Config::operator/ ( const float  downsampling_factor) const

Member Data Documentation

◆ fx

float se::PinholeCamera::Config::fx = std::numeric_limits<float>::quiet_NaN()

The sensor's horizontal focal length in pixels.

◆ fy

float se::PinholeCamera::Config::fy = std::numeric_limits<float>::quiet_NaN()

The sensor's vertical focal length in pixels.

◆ cx

float se::PinholeCamera::Config::cx = std::numeric_limits<float>::quiet_NaN()

The sensor's optical centre horizontal coordinate in pixels.

◆ cy

float se::PinholeCamera::Config::cy = std::numeric_limits<float>::quiet_NaN()

The sensor's optical centre vertical coordinate in pixels.


The documentation for this struct was generated from the following file: