Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its parameterization, rather than the transform from RW to camera coords. Uses static vars for camera params, so there is a single camera setup. More...
#include <types_icp.h>
Public Member Functions | |
void | mapPoint (Vector3d &res, const Vector3d &pt3) |
virtual void | oplus (double *update) |
update the position of the node from the parameters in v | |
virtual bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex | |
void | setAll () |
void | setDr () |
void | setProjection () |
void | setTransform () |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | VertexSCam () |
virtual bool | write (std::ostream &os) const |
write the vertex to a stream | |
Static Public Member Functions | |
static void | setKcam (double fx, double fy, double cx, double cy, double tx) |
static void | transformF2W (Matrix< double, 3, 4 > &m, const Vector3d &trans, const Quaterniond &qrot) |
static void | transformW2F (Matrix< double, 3, 4 > &m, const Vector3d &trans, const Quaterniond &qrot) |
Public Attributes | |
Matrix3d | dRdx |
Matrix3d | dRdy |
Matrix3d | dRdz |
Matrix< double, 3, 4 > | w2i |
Matrix< double, 3, 4 > | w2n |
Static Public Attributes | |
static double | baseline |
static Matrix3d | dRidx |
static Matrix3d | dRidy |
static Matrix3d | dRidz |
static Matrix3d | Kcam |
Stereo camera vertex, derived from SE3 class. Note that we use the actual pose of the vertex as its parameterization, rather than the transform from RW to camera coords. Uses static vars for camera params, so there is a single camera setup.
Definition at line 207 of file types_icp.h.
Definition at line 203 of file types_icp.cpp.
void g2o::VertexSCam::mapPoint | ( | Vector3d & | res, |
const Vector3d & | pt3 | ||
) | [inline] |
Definition at line 298 of file types_icp.h.
virtual void g2o::VertexSCam::oplus | ( | double * | v | ) | [inline, virtual] |
update the position of the node from the parameters in v
Reimplemented from g2o::VertexSE3.
Definition at line 219 of file types_icp.h.
bool g2o::VertexSCam::read | ( | std::istream & | is | ) | [virtual] |
read the vertex from a stream, i.e., the internal state of the vertex
Reimplemented from g2o::VertexSE3.
Definition at line 302 of file types_icp.cpp.
void g2o::VertexSCam::setAll | ( | ) | [inline] |
Definition at line 290 of file types_icp.h.
void g2o::VertexSCam::setDr | ( | ) | [inline] |
Definition at line 279 of file types_icp.h.
static void g2o::VertexSCam::setKcam | ( | double | fx, |
double | fy, | ||
double | cx, | ||
double | cy, | ||
double | tx | ||
) | [inline, static] |
Definition at line 259 of file types_icp.h.
void g2o::VertexSCam::setProjection | ( | ) | [inline] |
Definition at line 276 of file types_icp.h.
void g2o::VertexSCam::setTransform | ( | ) | [inline] |
Definition at line 271 of file types_icp.h.
static void g2o::VertexSCam::transformF2W | ( | Matrix< double, 3, 4 > & | m, |
const Vector3d & | trans, | ||
const Quaterniond & | qrot | ||
) | [inline, static] |
Definition at line 250 of file types_icp.h.
static void g2o::VertexSCam::transformW2F | ( | Matrix< double, 3, 4 > & | m, |
const Vector3d & | trans, | ||
const Quaterniond & | qrot | ||
) | [inline, static] |
Definition at line 238 of file types_icp.h.
bool g2o::VertexSCam::write | ( | std::ostream & | os | ) | const [virtual] |
write the vertex to a stream
Reimplemented from g2o::VertexSE3.
Definition at line 305 of file types_icp.cpp.
double g2o::VertexSCam::baseline [static] |
Definition at line 227 of file types_icp.h.
Matrix3d g2o::VertexSCam::dRdx |
Definition at line 235 of file types_icp.h.
Matrix3d g2o::VertexSCam::dRdy |
Definition at line 235 of file types_icp.h.
Matrix3d g2o::VertexSCam::dRdz |
Definition at line 235 of file types_icp.h.
Matrix3d g2o::VertexSCam::dRidx [static] |
Definition at line 315 of file types_icp.h.
Matrix3d g2o::VertexSCam::dRidy [static] |
Definition at line 315 of file types_icp.h.
Matrix3d g2o::VertexSCam::dRidz [static] |
Definition at line 315 of file types_icp.h.
Matrix3d g2o::VertexSCam::Kcam [static] |
Definition at line 226 of file types_icp.h.
Matrix<double,3,4> g2o::VertexSCam::w2i |
Definition at line 231 of file types_icp.h.
Matrix<double,3,4> g2o::VertexSCam::w2n |
Definition at line 230 of file types_icp.h.