00001 00024 #ifndef CCNY_RGBD_MOTION_ESTIMATION_H 00025 #define CCNY_RGBD_MOTION_ESTIMATION_H 00026 00027 #include <tf/transform_datatypes.h> 00028 #include <nav_msgs/Odometry.h> 00029 #include <boost/thread/mutex.hpp> 00030 00031 #include "ccny_rgbd/structures/rgbd_frame.h" 00032 00033 namespace ccny_rgbd { 00034 00040 class MotionEstimation 00041 { 00042 public: 00043 00044 enum MotionConstraint {NONE = 0, ROLL_PITCH = 1, ROLL_PITCH_Z = 2}; 00045 00050 MotionEstimation(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private); 00051 00054 virtual ~MotionEstimation(); 00055 00066 tf::Transform getMotionEstimation(RGBDFrame& frame); 00067 00072 void setBaseToCameraTf(const tf::Transform& b2c); 00073 00079 virtual int getModelSize() const { return 0; } 00080 00081 protected: 00082 00083 ros::NodeHandle nh_; 00084 ros::NodeHandle nh_private_; 00085 00086 tf::Transform b2c_; 00087 00088 int motion_constraint_; 00089 00097 virtual bool getMotionEstimationImpl( 00098 RGBDFrame& frame, 00099 const tf::Transform& prediction, 00100 tf::Transform& motion) = 0; 00101 00108 void constrainMotion(tf::Transform& motion); 00109 }; 00110 00111 } // namespace ccny_rgbd 00112 00113 #endif // CCNY_RGBD_MOTION_ESTIMATION_H