All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
rgbdtools::MotionEstimation Class Reference

Base class for visual odometry motion estimation methods. More...

#include <motion_estimation.h>

Inheritance diagram for rgbdtools::MotionEstimation:
Inheritance graph
[legend]

List of all members.

Public Types

enum  MotionConstraint {
  NONE = 0, ROLL_PITCH = 1, ROLL_PITCH_Z = 2, NONE = 0,
  ROLL_PITCH = 1, ROLL_PITCH_Z = 2
}
enum  MotionConstraint {
  NONE = 0, ROLL_PITCH = 1, ROLL_PITCH_Z = 2, NONE = 0,
  ROLL_PITCH = 1, ROLL_PITCH_Z = 2
}

Public Member Functions

virtual int getModelSize () const
 Return the size of the internal model. Overriden for classes that use a model.
virtual int getModelSize () const
 Return the size of the internal model. Overriden for classes that use a model.
AffineTransform getMotionEstimation (RGBDFrame &frame, const AffineTransform &prediction=AffineTransform::Identity())
 Main function for estimating motion.
AffineTransform getMotionEstimation (RGBDFrame &frame, const AffineTransform &prediction=AffineTransform::Identity())
 Main function for estimating motion.
 MotionEstimation ()
 Constructor from ROS nodehandles.
 MotionEstimation ()
 Constructor from ROS nodehandles.
void setBaseToCameraTf (const AffineTransform &b2c)
 Set the transformation between the base and camera frames.
void setBaseToCameraTf (const AffineTransform &b2c)
 Set the transformation between the base and camera frames.
void setMotionConstraint (int motion_constraint)
void setMotionConstraint (int motion_constraint)
virtual ~MotionEstimation ()
 Default destructor.
virtual ~MotionEstimation ()
 Default destructor.

Protected Member Functions

void constrainMotion (AffineTransform &motion)
 Constrains the motion in accordance to the class motion constraints.
void constrainMotion (AffineTransform &motion)
 Constrains the motion in accordance to the class motion constraints.
virtual bool getMotionEstimationImpl (RGBDFrame &frame, const AffineTransform &prediction, AffineTransform &motion)=0
 Implementation of the motion estimation algorithm.
virtual bool getMotionEstimationImpl (RGBDFrame &frame, const AffineTransform &prediction, AffineTransform &motion)=0
 Implementation of the motion estimation algorithm.

Protected Attributes

AffineTransform b2c_
 Base (moving) frame to Camera-optical frame.
int motion_constraint_
 The motion constraint type.

Detailed Description

Base class for visual odometry motion estimation methods.

The motion is estimated in increments of the change of pose of the base frame. The increments are expressed wrt fixed frame.

Definition at line 39 of file include/rgbdtools/registration/motion_estimation.h.


Member Enumeration Documentation

Enumerator:
NONE 
ROLL_PITCH 
ROLL_PITCH_Z 
NONE 
ROLL_PITCH 
ROLL_PITCH_Z 

Definition at line 43 of file include/rgbdtools/registration/motion_estimation.h.

Enumerator:
NONE 
ROLL_PITCH 
ROLL_PITCH_Z 
NONE 
ROLL_PITCH 
ROLL_PITCH_Z 

Definition at line 43 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation.h.


Constructor & Destructor Documentation

Constructor from ROS nodehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private nodehandle

Definition at line 28 of file motion_estimation.cpp.

Default destructor.

Definition at line 33 of file motion_estimation.cpp.

Constructor from ROS nodehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private nodehandle

Default destructor.


Member Function Documentation

Constrains the motion in accordance to the class motion constraints.

This method can be called by the inheriting classes if desired.

Parameters:
motionthe incremental motion which is constrained.

Definition at line 67 of file motion_estimation.cpp.

Constrains the motion in accordance to the class motion constraints.

This method can be called by the inheriting classes if desired.

Parameters:
motionthe incremental motion which is constrained.
virtual int rgbdtools::MotionEstimation::getModelSize ( ) const [inline, virtual]

Return the size of the internal model. Overriden for classes that use a model.

Returns:
the size of the model

Reimplemented in rgbdtools::MotionEstimationICPProbModel, and rgbdtools::MotionEstimationICPProbModel.

Definition at line 82 of file rgbdtools_git/include/rgbdtools/registration/motion_estimation.h.

virtual int rgbdtools::MotionEstimation::getModelSize ( ) const [inline, virtual]

Return the size of the internal model. Overriden for classes that use a model.

Returns:
the size of the model

Reimplemented in rgbdtools::MotionEstimationICPProbModel, and rgbdtools::MotionEstimationICPProbModel.

Definition at line 82 of file include/rgbdtools/registration/motion_estimation.h.

AffineTransform rgbdtools::MotionEstimation::getMotionEstimation ( RGBDFrame frame,
const AffineTransform prediction = AffineTransform::Identity() 
)

Main function for estimating motion.

The motion is equal to the change of pose of the base frame, and is expressed wrt the fixed frame

Pose_new = motion * Pose_old;

Parameters:
frameThe RGBD Frame for which the motion is estimated
Returns:
incremental motion transform
Todo:
this should return a covariance

Definition at line 38 of file motion_estimation.cpp.

AffineTransform rgbdtools::MotionEstimation::getMotionEstimation ( RGBDFrame frame,
const AffineTransform prediction = AffineTransform::Identity() 
)

Main function for estimating motion.

The motion is equal to the change of pose of the base frame, and is expressed wrt the fixed frame

Pose_new = motion * Pose_old;

Parameters:
frameThe RGBD Frame for which the motion is estimated
Returns:
incremental motion transform
virtual bool rgbdtools::MotionEstimation::getMotionEstimationImpl ( RGBDFrame frame,
const AffineTransform prediction,
AffineTransform motion 
) [protected, pure virtual]

Implementation of the motion estimation algorithm.

Parameters:
framethe current RGBD frame
predictionthe motion prediction (currently ignored)
motionthe output motion
Return values:
truethe motion estimation was successful
falsethe motion estimation failed

Implemented in rgbdtools::MotionEstimationPairwiseRANSAC, rgbdtools::MotionEstimationPairwiseRANSAC, rgbdtools::MotionEstimationICPProbModel, and rgbdtools::MotionEstimationICPProbModel.

virtual bool rgbdtools::MotionEstimation::getMotionEstimationImpl ( RGBDFrame frame,
const AffineTransform prediction,
AffineTransform motion 
) [protected, pure virtual]

Implementation of the motion estimation algorithm.

Parameters:
framethe current RGBD frame
predictionthe motion prediction (currently ignored)
motionthe output motion
Return values:
truethe motion estimation was successful
falsethe motion estimation failed

Implemented in rgbdtools::MotionEstimationPairwiseRANSAC, rgbdtools::MotionEstimationPairwiseRANSAC, rgbdtools::MotionEstimationICPProbModel, and rgbdtools::MotionEstimationICPProbModel.

Set the transformation between the base and camera frames.

Parameters:
b2cThe transform from the base frame to the camera frame, expressed wrt the base frame.

Set the transformation between the base and camera frames.

Parameters:
b2cThe transform from the base frame to the camera frame, expressed wrt the base frame.

Definition at line 85 of file motion_estimation.cpp.

void rgbdtools::MotionEstimation::setMotionConstraint ( int  motion_constraint)

Definition at line 90 of file motion_estimation.cpp.

void rgbdtools::MotionEstimation::setMotionConstraint ( int  motion_constraint)

Member Data Documentation

Base (moving) frame to Camera-optical frame.

Definition at line 86 of file include/rgbdtools/registration/motion_estimation.h.

The motion constraint type.

Definition at line 88 of file include/rgbdtools/registration/motion_estimation.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:55