|
g2o
|
#include <se2.h>
Public Member Functions | |
| SE2 () | |
| SE2 (const Isometry2 &iso) | |
| SE2 (const Vector3 &v) | |
| SE2 (double x, double y, double theta) | |
| const Vector2 & | translation () const |
| translational component | |
| void | setTranslation (const Vector2 &t_) |
| const Rotation2D & | rotation () const |
| rotational component | |
| void | setRotation (const Rotation2D &R_) |
| SE2 | operator* (const SE2 &tr2) const |
| concatenate two SE2 elements (motion composition) | |
| SE2 & | operator*= (const SE2 &tr2) |
| motion composition operator | |
| Vector2 | operator* (const Vector2 &v) const |
| project a 2D vector | |
| SE2 | inverse () const |
| invert :-) | |
| double | operator[] (int i) const |
| void | fromVector (const Vector3 &v) |
| assign from a 3D vector (x, y, theta) | |
| Vector3 | toVector () const |
| convert to a 3D vector (x, y, theta) | |
| Isometry2 | toIsometry () const |
Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Protected Attributes | |
| Rotation2D | _R |
| Vector2 | _t |
|
inline |
|
inline |
|
inline |
|
inline |
assign from a 3D vector (x, y, theta)
Definition at line 102 of file se2.h.
Referenced by g2o::EdgeSE2PureCalib::computeError(), EdgeCalib::computeError(), g2o::EdgeSE2OdomDifferentialCalib::computeError(), main(), g2o::tutorial::VertexSE2::read(), and g2o::Gm2dlIO::readGm2dl().
|
inline |
invert :-)
Definition at line 83 of file se2.h.
References _R, _t, and g2o::normalize_theta().
Referenced by g2o::addOdometryCalibLinksDifferential(), g2o::OnlineEdgeSE2::chi2(), g2o::EdgeSE2PureCalib::computeError(), EdgeCalib::computeError(), g2o::tutorial::EdgeSE2::computeError(), g2o::EdgeSE2OdomDifferentialCalib::computeError(), g2o::EdgeSE2::computeError(), g2o::EdgeSE2LotsOfXY::computeError(), g2o::EdgeSE2PointXY::computeError(), g2o::EdgeSE2PointXYBearing::computeError(), g2o::EdgeSE2TwoPointsXY::computeError(), g2o::EdgeSE2Line2D::computeError(), g2o::EdgeSE2Segment2D::computeError(), g2o::EdgeSE2Segment2DLine::computeError(), g2o::EdgeSE2Segment2DPointLine::computeError(), g2o::EdgeSE2SensorCalib::initialEstimate(), g2o::EdgeSE2Offset::initialEstimate(), g2o::SensorSegment2D::isVisible(), g2o::SensorSegment2DLine::isVisible(), g2o::SensorSegment2DPointLine::isVisible(), main(), g2o::RobotLaser::read(), g2o::EdgeSE2SensorCalib::read(), g2o::EdgeSE2::read(), g2o::EdgeSE2Prior::read(), g2o::Gm2dlIO::readGm2dl(), g2o::EdgeSE2SensorCalib::setMeasurement(), g2o::EdgeSE2::setMeasurement(), g2o::EdgeSE2Offset::setMeasurement(), g2o::EdgeSE2Prior::setMeasurement(), g2o::EdgeSE2Prior::setMeasurementData(), g2o::EdgeSE2::setMeasurementFromState(), g2o::EdgeSE2LotsOfXY::setMeasurementFromState(), g2o::EdgeSE2PointXY::setMeasurementFromState(), g2o::EdgeSE2PointXYBearing::setMeasurementFromState(), g2o::EdgeSE2TwoPointsXY::setMeasurementFromState(), g2o::EdgeSE2Line2D::setMeasurementFromState(), g2o::EdgeSE2Segment2D::setMeasurementFromState(), g2o::EdgeSE2Segment2DLine::setMeasurementFromState(), g2o::EdgeSE2Segment2DPointLine::setMeasurementFromState(), and g2o::CacheSE2Offset::updateImpl().
|
inline |
|
inline |
rotational component
Definition at line 61 of file se2.h.
Referenced by g2o::addOdometryCalibLinksDifferential(), g2o::ClosedFormCalibration::calibrate(), g2o::EdgeSE2Offset::computeError(), g2o::EdgeSE2Line2D::computeError(), g2o::EdgeSE2PointXYBearing::initialEstimate(), g2o::EdgeSE2Line2D::initialEstimate(), g2o::EdgeSE2::linearizeOplus(), g2o::EdgeSE2LotsOfXY::linearizeOplus(), g2o::EdgeSE2PointXY::linearizeOplus(), main(), g2o::EdgeSE2WriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYWriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYBearingWriteGnuplotAction::operator()(), g2o::VertexSE2WriteGnuplotAction::operator()(), g2o::operator*(), g2o::G2oSlamInterface::printVertex(), g2o::EdgeSE2Line2D::setMeasurementFromState(), g2o::ParameterSE2Offset::setOffset(), updateDisplay(), and g2o::CacheSE2Offset::updateImpl().
|
inline |
Definition at line 62 of file se2.h.
Referenced by g2o::EdgeSE2PointXYBearing::initialEstimate(), and main().
|
inline |
|
inline |
|
inline |
convert to a 3D vector (x, y, theta)
Definition at line 105 of file se2.h.
Referenced by g2o::OnlineEdgeSE2::chi2(), g2o::EdgeSE2PureCalib::computeError(), EdgeCalib::computeError(), g2o::EdgeSE2OdomDifferentialCalib::computeError(), g2o::EdgeSE2SensorCalib::computeError(), g2o::EdgeSE2::computeError(), g2o::EdgeSE2Prior::computeError(), gnudump_edges(), main(), g2o::tutorial::VertexSE2::write(), and g2o::RobotLaser::write().
|
inline |
translational component
Definition at line 57 of file se2.h.
Referenced by g2o::addOdometryCalibLinksDifferential(), g2o::ClosedFormCalibration::calibrate(), g2o::EdgeSE2Offset::computeError(), g2o::EdgeSE2XYPrior::computeError(), g2o::EdgeSE2Line2D::computeError(), g2o::Slam2DViewer::draw(), g2o::SparseOptimizerOnline::gnuplotVisualization(), g2o::EdgeSE2Line2D::initialEstimate(), g2o::EdgeSE2::linearizeOplus(), g2o::EdgeSE2LotsOfXY::linearizeOplus(), g2o::EdgeSE2PointXY::linearizeOplus(), g2o::EdgeSE2PointXYOffset::linearizeOplus(), main(), g2o::EdgeSE2WriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYWriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYBearingWriteGnuplotAction::operator()(), g2o::VertexSE2WriteGnuplotAction::operator()(), g2o::operator*(), g2o::G2oSlamInterface::printVertex(), g2o::EdgeSE2Line2D::setMeasurementFromState(), g2o::ParameterSE2Offset::setOffset(), updateDisplay(), and g2o::CacheSE2Offset::updateImpl().
|
protected |
Definition at line 117 of file se2.h.
Referenced by inverse(), and operator*=().
|
protected |
Definition at line 118 of file se2.h.
Referenced by inverse(), and operator*=().