SaDVIO
Public Member Functions | Public Attributes | Static Public Attributes | List of all members
isae::PointXYZParametersBlock Class Reference

A Parameter block for 3D position that does the interface between a double* and an Eigen::Vector3d. More...

#include <parametersBlock.hpp>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PointXYZParametersBlock ()
 
 PointXYZParametersBlock (const Eigen::Vector3d &X)
 
 PointXYZParametersBlock (const PointXYZParametersBlock &block)
 
PointXYZParametersBlockoperator= (const PointXYZParametersBlock &block)
 
Eigen::Affine3d getPose ()
 
double * values ()
 

Public Attributes

double values_ [ndim_] = {0., 0., 0.}
 

Static Public Attributes

static const size_t ndim_ = 3
 

Detailed Description

A Parameter block for 3D position that does the interface between a double* and an Eigen::Vector3d.

Constructor & Destructor Documentation

◆ PointXYZParametersBlock() [1/3]

EIGEN_MAKE_ALIGNED_OPERATOR_NEW isae::PointXYZParametersBlock::PointXYZParametersBlock ( )
inline

◆ PointXYZParametersBlock() [2/3]

isae::PointXYZParametersBlock::PointXYZParametersBlock ( const Eigen::Vector3d &  X)
inline

◆ PointXYZParametersBlock() [3/3]

isae::PointXYZParametersBlock::PointXYZParametersBlock ( const PointXYZParametersBlock block)
inline

Member Function Documentation

◆ getPose()

Eigen::Affine3d isae::PointXYZParametersBlock::getPose ( )
inline

◆ operator=()

PointXYZParametersBlock& isae::PointXYZParametersBlock::operator= ( const PointXYZParametersBlock block)
inline

◆ values()

double* isae::PointXYZParametersBlock::values ( )
inline

Member Data Documentation

◆ ndim_

const size_t isae::PointXYZParametersBlock::ndim_ = 3
static

◆ values_

double isae::PointXYZParametersBlock::values_[ndim_] = {0., 0., 0.}

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