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

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

#include <motion_estimation.h>

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

List of all members.

Public Types

enum  MotionConstraint { 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.
tf::Transform getMotionEstimation (RGBDFrame &frame)
 Main function for estimating motion.
 MotionEstimation (const ros::NodeHandle &nh, const ros::NodeHandle &nh_private)
 Constructor from ROS nodehandles.
void setBaseToCameraTf (const tf::Transform &b2c)
 Set the transformation between the base and camera frames.
virtual ~MotionEstimation ()
 Default destructor.

Protected Member Functions

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

Protected Attributes

tf::Transform b2c_
 Base (moving) frame to Camera-optical frame.
int motion_constraint_
 The motion constraint type.
ros::NodeHandle nh_
 The public nodehandle.
ros::NodeHandle nh_private_
 The private nodehandle.

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 40 of file motion_estimation.h.


Member Enumeration Documentation

Enumerator:
NONE 
ROLL_PITCH 
ROLL_PITCH_Z 

Definition at line 44 of file 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 39 of file motion_estimation.cpp.


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 75 of file motion_estimation.cpp.

virtual int ccny_rgbd::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 ccny_rgbd::MotionEstimationICPProbModel, and ccny_rgbd::MotionEstimationICP.

Definition at line 79 of file motion_estimation.h.

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
Todo:
motion prediction disabled for now

Definition at line 44 of file motion_estimation.cpp.

virtual bool ccny_rgbd::MotionEstimation::getMotionEstimationImpl ( RGBDFrame frame,
const tf::Transform prediction,
tf::Transform 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 ccny_rgbd::MotionEstimationICPProbModel, and ccny_rgbd::MotionEstimationICP.

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 98 of file motion_estimation.cpp.


Member Data Documentation

Base (moving) frame to Camera-optical frame.

Definition at line 86 of file motion_estimation.h.

The motion constraint type.

Definition at line 88 of file motion_estimation.h.

The public nodehandle.

Definition at line 83 of file motion_estimation.h.

The private nodehandle.

Definition at line 84 of file motion_estimation.h.


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


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Fri Apr 12 2013 20:38:48