Public Member Functions | Public Attributes | Static Public Attributes | Private Member Functions | Private Attributes
qglv::KeyFrame Class Reference

#include <keyframes.hpp>

List of all members.

Public Member Functions

void draw (bool draw_frames=true, bool draw_seeds=false, bool draw_covariances=false)
 KeyFrame ()
 KeyFrame (const int id, const Sophus::SE3f &T_frame_rel_map, const AxisColourScheme &axis_colour_scheme=AxisColourRGB, const float &axis_scale_factor=1.0)
 KeyFrame (const int id, const Sophus::SE3f &T, const bool &pinned, const std::vector< Eigen::Vector3f > &seeds, const std::vector< float > &seed_variances, const std::vector< unsigned char > &seed_intensities, const float &focal_length_times_baseline)
 KeyFrame (const int id, const Sophus::SE3f &T, const bool &pinned, const std::vector< float > &nics, const std::vector< float > &idepths, const std::vector< float > &seed_variances, const std::vector< unsigned char > &seed_intensities_and_grad, const float &focal_length_times_baseline)
 KeyFrame (const Sophus::SE3f &T, const std::vector< float > &nics, const std::vector< float > &idepths, const std::vector< float > &seed_variances, const std::vector< unsigned char > &seed_intensities_and_grad)
void setName (const std::string &name)
 ~KeyFrame ()

Public Attributes

AxisColourScheme axis_colour_scheme
float axis_scale_factor
int id
 Id number of this frame.
std::vector< unsigned char > intensities
 Flag denoting if it was new/updated recently.
bool pinned
 If the keyframe is pinned, we draw it differently.
Sophus::SE3f T_frame_rel_map
 6D information
bool updated
std::vector< float > variance_lines
std::vector< float > vertices

Static Public Attributes

static const float default_keyframe_size = 0.3

Private Member Functions

void _glGenLists ()

Private Attributes

int gl_id_start
 Opengl id starting point for the lists.
std::string name

Detailed Description

Data for each depth frame. This essentially packages the statistics gathered DepthFrame with a structure that can be neatly packaged off to the gui thread for consumption.

It does some pre-computation before sending, and gllists computation after arriving. Also, once it is sent off to the gui receiver to be invoked the gui thread, local control over the object is surrendered to the gui thread.

It is also possible to generate keyframes from point clouds. Refer to the qglv_pcl package for api.

Definition at line 42 of file keyframes.hpp.


Constructor & Destructor Documentation

Definition at line 45 of file keyframes.hpp.

qglv::KeyFrame::KeyFrame ( const int  id,
const Sophus::SE3f &  T_frame_rel_map,
const AxisColourScheme axis_colour_scheme = AxisColourRGB,
const float &  axis_scale_factor = 1.0 
)

Generate without any cloud information;

Definition at line 29 of file keyframes.cpp.

qglv::KeyFrame::KeyFrame ( const int  id,
const Sophus::SE3f &  T,
const bool &  pinned,
const std::vector< Eigen::Vector3f > &  seeds,
const std::vector< float > &  seed_variances,
const std::vector< unsigned char > &  seed_intensities,
const float &  focal_length_times_baseline 
)

Generate from simple dslam pc keyframe data.

Definition at line 182 of file keyframes.cpp.

qglv::KeyFrame::KeyFrame ( const int  id,
const Sophus::SE3f &  T,
const bool &  pinned,
const std::vector< float > &  nics,
const std::vector< float > &  idepths,
const std::vector< float > &  seed_variances,
const std::vector< unsigned char > &  seed_intensities_and_grad,
const float &  focal_length_times_baseline 
)

Generate from simple dslam pc keyframe data.

Definition at line 109 of file keyframes.cpp.

qglv::KeyFrame::KeyFrame ( const Sophus::SE3f &  T,
const std::vector< float > &  nics,
const std::vector< float > &  idepths,
const std::vector< float > &  seed_variances,
const std::vector< unsigned char > &  seed_intensities_and_grad 
)

Generate from a tracking frame.

Definition at line 48 of file keyframes.cpp.

Definition at line 252 of file keyframes.cpp.


Member Function Documentation

void qglv::KeyFrame::_glGenLists ( ) [private]

Definition at line 276 of file keyframes.cpp.

void qglv::KeyFrame::draw ( bool  draw_frames = true,
bool  draw_seeds = false,
bool  draw_covariances = false 
)

Definition at line 258 of file keyframes.cpp.

void qglv::KeyFrame::setName ( const std::string &  name)

Member Data Documentation

Definition at line 108 of file keyframes.hpp.

Definition at line 109 of file keyframes.hpp.

const float qglv::KeyFrame::default_keyframe_size = 0.3 [static]

Definition at line 110 of file keyframes.hpp.

Opengl id starting point for the lists.

Definition at line 120 of file keyframes.hpp.

Id number of this frame.

Definition at line 106 of file keyframes.hpp.

std::vector<unsigned char> qglv::KeyFrame::intensities

Flag denoting if it was new/updated recently.

Definition at line 113 of file keyframes.hpp.

std::string qglv::KeyFrame::name [private]

Definition at line 121 of file keyframes.hpp.

If the keyframe is pinned, we draw it differently.

Definition at line 111 of file keyframes.hpp.

6D information

Definition at line 107 of file keyframes.hpp.

Definition at line 112 of file keyframes.hpp.

std::vector<float> qglv::KeyFrame::variance_lines

Definition at line 115 of file keyframes.hpp.

std::vector<float> qglv::KeyFrame::vertices

Definition at line 114 of file keyframes.hpp.


The documentation for this class was generated from the following files:


qglv_opengl
Author(s): Daniel Stonier
autogenerated on Sat Jun 18 2016 08:19:28