#include <NonLinearLS.h>
Public Member Functions | |
Matrix4 | getCamera (bool Twc=false) |
Matrix4 | getCamera (bool Twc=false) |
Vector2d | map (const Vector3 &Pw) |
Vector2d | map (const Vector3 &Pw) |
virtual void | oplus (double *update_) |
update the position of the node from the parameters in v | |
virtual void | oplus (double *update_) |
update the position of the node from the parameters in v | |
void | pop () |
restore the position of the vertex by retrieving the position from the stack | |
void | pop () |
restore the position of the vertex by retrieving the position from the stack | |
void | push () |
backup the position of the vertex to a stack | |
void | push () |
backup the position of the vertex to a stack | |
bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex | |
bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex | |
virtual void | setToOrigin () |
sets the node to the origin (used in the multilevel stuff) | |
virtual void | setToOrigin () |
sets the node to the origin (used in the multilevel stuff) | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | VertexSE3AxisAngle (Vector6 calibracion) |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | VertexSE3AxisAngle (Vector6 calibracion) |
VertexSE3AxisAngle (Vector6 calibracion, Vector6 mu, bool Twc=false) | |
VertexSE3AxisAngle (Vector6 calibracion, Vector6 mu, bool Twc=false) | |
VertexSE3AxisAngle (Vector6 calibracion, Matrix4 T, bool Twc=false) | |
VertexSE3AxisAngle (Vector6 calibracion, Matrix4 T, bool Twc=false) | |
bool | write (std::ostream &os) const |
write the vertex to a stream | |
bool | write (std::ostream &os) const |
write the vertex to a stream | |
Private Types | |
typedef Matrix< double, 3, 4 > | RtMatrix |
typedef Matrix< double, 3, 4 > | RtMatrix |
Private Attributes | |
std::stack< RtMatrix * > | backups |
Vector6 | K |
Matrix3 | Rcw |
Vector3 | tcw |
bool | Twc |
Aligment transformation
Definition at line 172 of file g2o/g2o/examples/dorian/NonLinearLS.h.
typedef Matrix<double, 3, 4> g2o::VertexSE3AxisAngle::RtMatrix [private] |
Definition at line 316 of file g2o/g2o/examples/dorian/NonLinearLS.h.
typedef Matrix<double, 3, 4> g2o::VertexSE3AxisAngle::RtMatrix [private] |
Definition at line 316 of file NonLinearLS.h.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW g2o::VertexSE3AxisAngle::VertexSE3AxisAngle | ( | Vector6 | calibracion | ) | [inline] |
Definition at line 177 of file g2o/g2o/examples/dorian/NonLinearLS.h.
g2o::VertexSE3AxisAngle::VertexSE3AxisAngle | ( | Vector6 | calibracion, |
Vector6 | mu, | ||
bool | Twc = false |
||
) | [inline] |
Definition at line 185 of file g2o/g2o/examples/dorian/NonLinearLS.h.
g2o::VertexSE3AxisAngle::VertexSE3AxisAngle | ( | Vector6 | calibracion, |
Matrix4 | T, | ||
bool | Twc = false |
||
) | [inline] |
Definition at line 205 of file g2o/g2o/examples/dorian/NonLinearLS.h.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW g2o::VertexSE3AxisAngle::VertexSE3AxisAngle | ( | Vector6 | calibracion | ) | [inline] |
Definition at line 177 of file NonLinearLS.h.
g2o::VertexSE3AxisAngle::VertexSE3AxisAngle | ( | Vector6 | calibracion, |
Vector6 | mu, | ||
bool | Twc = false |
||
) | [inline] |
Definition at line 185 of file NonLinearLS.h.
g2o::VertexSE3AxisAngle::VertexSE3AxisAngle | ( | Vector6 | calibracion, |
Matrix4 | T, | ||
bool | Twc = false |
||
) | [inline] |
Definition at line 205 of file NonLinearLS.h.
Matrix4 g2o::VertexSE3AxisAngle::getCamera | ( | bool | Twc = false | ) | [inline] |
Definition at line 296 of file g2o/g2o/examples/dorian/NonLinearLS.h.
Matrix4 g2o::VertexSE3AxisAngle::getCamera | ( | bool | Twc = false | ) | [inline] |
Definition at line 296 of file NonLinearLS.h.
Vector2d g2o::VertexSE3AxisAngle::map | ( | const Vector3 & | Pw | ) | [inline] |
Definition at line 244 of file g2o/g2o/examples/dorian/NonLinearLS.h.
Vector2d g2o::VertexSE3AxisAngle::map | ( | const Vector3 & | Pw | ) | [inline] |
Definition at line 244 of file NonLinearLS.h.
virtual void g2o::VertexSE3AxisAngle::oplus | ( | double * | v | ) | [inline, virtual] |
update the position of the node from the parameters in v
Implements g2o::OptimizableGraph::Vertex.
Definition at line 230 of file g2o/g2o/examples/dorian/NonLinearLS.h.
virtual void g2o::VertexSE3AxisAngle::oplus | ( | double * | v | ) | [inline, virtual] |
update the position of the node from the parameters in v
Implements g2o::OptimizableGraph::Vertex.
Definition at line 230 of file NonLinearLS.h.
void g2o::VertexSE3AxisAngle::pop | ( | ) | [inline, virtual] |
restore the position of the vertex by retrieving the position from the stack
Reimplemented from g2o::BaseVertex< 6, SE3AxisAngle >.
Definition at line 282 of file g2o/g2o/examples/dorian/NonLinearLS.h.
void g2o::VertexSE3AxisAngle::pop | ( | ) | [inline, virtual] |
restore the position of the vertex by retrieving the position from the stack
Reimplemented from g2o::BaseVertex< 6, SE3AxisAngle >.
Definition at line 282 of file NonLinearLS.h.
void g2o::VertexSE3AxisAngle::push | ( | ) | [inline, virtual] |
backup the position of the vertex to a stack
Reimplemented from g2o::BaseVertex< 6, SE3AxisAngle >.
Definition at line 270 of file NonLinearLS.h.
void g2o::VertexSE3AxisAngle::push | ( | ) | [inline, virtual] |
backup the position of the vertex to a stack
Reimplemented from g2o::BaseVertex< 6, SE3AxisAngle >.
Definition at line 270 of file g2o/g2o/examples/dorian/NonLinearLS.h.
bool g2o::VertexSE3AxisAngle::read | ( | std::istream & | is | ) | [inline, virtual] |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Vertex.
Definition at line 221 of file NonLinearLS.h.
bool g2o::VertexSE3AxisAngle::read | ( | std::istream & | is | ) | [inline, virtual] |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Vertex.
Definition at line 221 of file g2o/g2o/examples/dorian/NonLinearLS.h.
virtual void g2o::VertexSE3AxisAngle::setToOrigin | ( | ) | [inline, virtual] |
sets the node to the origin (used in the multilevel stuff)
Implements g2o::OptimizableGraph::Vertex.
Definition at line 226 of file NonLinearLS.h.
virtual void g2o::VertexSE3AxisAngle::setToOrigin | ( | ) | [inline, virtual] |
sets the node to the origin (used in the multilevel stuff)
Implements g2o::OptimizableGraph::Vertex.
Definition at line 226 of file g2o/g2o/examples/dorian/NonLinearLS.h.
bool g2o::VertexSE3AxisAngle::write | ( | std::ostream & | os | ) | const [inline, virtual] |
write the vertex to a stream
Implements g2o::OptimizableGraph::Vertex.
Definition at line 222 of file g2o/g2o/examples/dorian/NonLinearLS.h.
bool g2o::VertexSE3AxisAngle::write | ( | std::ostream & | os | ) | const [inline, virtual] |
write the vertex to a stream
Implements g2o::OptimizableGraph::Vertex.
Definition at line 222 of file NonLinearLS.h.
std::stack< RtMatrix * > g2o::VertexSE3AxisAngle::backups [private] |
Definition at line 318 of file g2o/g2o/examples/dorian/NonLinearLS.h.
Vector6 g2o::VertexSE3AxisAngle::K [private] |
Definition at line 324 of file g2o/g2o/examples/dorian/NonLinearLS.h.
Matrix3 g2o::VertexSE3AxisAngle::Rcw [private] |
Definition at line 322 of file g2o/g2o/examples/dorian/NonLinearLS.h.
Vector3 g2o::VertexSE3AxisAngle::tcw [private] |
Definition at line 323 of file g2o/g2o/examples/dorian/NonLinearLS.h.
bool g2o::VertexSE3AxisAngle::Twc [private] |
Definition at line 321 of file g2o/g2o/examples/dorian/NonLinearLS.h.