Sensor model for PrimeSense cameras. More...
#include <sensor_model.h>
Public Types | |
typedef Eigen::Map< const Eigen::Matrix< float, 4, 4, Eigen::RowMajor > > | MatMap |
Public Member Functions | |
PrimeSense () | |
Empty constructor. | |
~PrimeSense () | |
Empty destructor. | |
Static Public Member Functions | |
static bool | areNeighbors (float query, float neighbor, float tolerance=2.0f) |
static bool | areNeighbors (const Eigen::Vector3f &query, const Eigen::Vector3f &neighbor, float tolerance=4.0f) |
static Eigen::Matrix4f | tf_unit_cube () |
Static Public Attributes | |
static const float | aspect = PrimeSense::w / PrimeSense::h |
static const float | b = - PrimeSense::t |
bottom | |
static const float | f = 5.0f |
far plane | |
static const float | fov_h = 49.0f / 180.0f * M_PI |
fov horizontal (IR) , from wiki and ros.org | |
static const float | fov_v = 43.0f / 180.0f * M_PI |
fov vertical (IR) | |
static const float | h = 480.0f |
static const float | l = - PrimeSense::r |
left | |
static const float | mat [] |
static const float | n = 0.5f |
near plane | |
static const float | r = PrimeSense::n * tan(PrimeSense::fov_h * 0.5f) |
right | |
static const float | t = PrimeSense::n * tan(PrimeSense::fov_v * 0.5f) |
top | |
static const float | w = 640.0f |
Sensor model for PrimeSense cameras.
Definition at line 75 of file sensor_model.h.
typedef Eigen::Map<const Eigen::Matrix<float,4,4,Eigen::RowMajor> > cob_3d_mapping::PrimeSense::MatMap |
Definition at line 78 of file sensor_model.h.
cob_3d_mapping::PrimeSense::PrimeSense | ( | ) | [inline] |
Empty constructor.
Definition at line 83 of file sensor_model.h.
cob_3d_mapping::PrimeSense::~PrimeSense | ( | ) | [inline] |
Empty destructor.
Definition at line 87 of file sensor_model.h.
static bool cob_3d_mapping::PrimeSense::areNeighbors | ( | float | query, |
float | neighbor, | ||
float | tolerance = 2.0f |
||
) | [inline, static] |
Definition at line 98 of file sensor_model.h.
static bool cob_3d_mapping::PrimeSense::areNeighbors | ( | const Eigen::Vector3f & | query, |
const Eigen::Vector3f & | neighbor, | ||
float | tolerance = 4.0f |
||
) | [inline, static] |
Definition at line 116 of file sensor_model.h.
static Eigen::Matrix4f cob_3d_mapping::PrimeSense::tf_unit_cube | ( | ) | [inline, static] |
Definition at line 126 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::aspect = PrimeSense::w / PrimeSense::h [static] |
Definition at line 139 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::b = - PrimeSense::t [static] |
bottom
Definition at line 136 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::f = 5.0f [static] |
far plane
Definition at line 131 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::fov_h = 49.0f / 180.0f * M_PI [static] |
fov horizontal (IR) , from wiki and ros.org
Definition at line 129 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::fov_v = 43.0f / 180.0f * M_PI [static] |
fov vertical (IR)
Definition at line 130 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::h = 480.0f [static] |
Definition at line 138 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::l = - PrimeSense::r [static] |
left
Definition at line 133 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::mat [static] |
{ 1.0f / ( PrimeSense::aspect * tan(0.5f * PrimeSense::fov_h) ), 0, 0, 0, 0, 1.0f / ( tan(0.5f * PrimeSense::fov_h) ), 0, 0, 0, 0, (PrimeSense::n + PrimeSense::f) / (PrimeSense::n - PrimeSense::f), -2.0f * PrimeSense::f * PrimeSense::n / (PrimeSense::n - PrimeSense::f), 0, 0, 1, 0 }
Definition at line 140 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::n = 0.5f [static] |
near plane
Definition at line 132 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::r = PrimeSense::n * tan(PrimeSense::fov_h * 0.5f) [static] |
right
Definition at line 134 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::t = PrimeSense::n * tan(PrimeSense::fov_v * 0.5f) [static] |
top
Definition at line 135 of file sensor_model.h.
const float cob_3d_mapping::PrimeSense::w = 640.0f [static] |
Definition at line 137 of file sensor_model.h.