Skip to content

Commit

Permalink
image area on wall is optimized (max area with given ratio), content …
Browse files Browse the repository at this point in the history
…from main screen is copied to projector
  • Loading branch information
Nikolas Engelhard committed May 14, 2012
1 parent 05e5848 commit ab1a712
Show file tree
Hide file tree
Showing 4 changed files with 279 additions and 51 deletions.
15 changes: 15 additions & 0 deletions README
@@ -1,5 +1,20 @@
Kinect-Touchscreen Kinect-Touchscreen




Current State:
Calibration from a single image, content of Main Screen is shown on Projector.
Size of screens has to be edited by hand, check main.cpp l. 53 and projector_calibrator.h l. 181










see the imgs/ to see the current status! see the imgs/ to see the current status!


The goal of this project is to build a prototype for a large touchscreen The goal of this project is to build a prototype for a large touchscreen
Expand Down
22 changes: 19 additions & 3 deletions include/projector_calibrator.h
Expand Up @@ -17,6 +17,9 @@
#include <opencv2/imgproc/imgproc.hpp> #include <opencv2/imgproc/imgproc.hpp>
#include <pcl/common/transform.h> #include <pcl/common/transform.h>


typedef cv::Rect_<float> cv_RectF;


class Projector_Calibrator { class Projector_Calibrator {




Expand All @@ -32,8 +35,7 @@ class Projector_Calibrator {
// a simple image for debugging // a simple image for debugging
cv::Mat test_img; cv::Mat test_img;


// apply on image
cv::Mat warp_matrix;


// trafo cloud s.t. checkerboard is z=0, middle of board at x=y=0 // trafo cloud s.t. checkerboard is z=0, middle of board at x=y=0
// the first trafo is stored and used for all following frames // the first trafo is stored and used for all following frames
Expand Down Expand Up @@ -67,6 +69,8 @@ class Projector_Calibrator {
// remove all point from the input cloud where mask!=255 // remove all point from the input cloud where mask!=255
void applyMaskOnInputCloud(Cloud& out); void applyMaskOnInputCloud(Cloud& out);




// fit a plane into the pointcloud // fit a plane into the pointcloud
float fitPlaneToCloud(const Cloud& cloud, Eigen::Vector4f& model); float fitPlaneToCloud(const Cloud& cloud, Eigen::Vector4f& model);


Expand All @@ -89,8 +93,17 @@ class Projector_Calibrator {
bool saveMat(const std::string name, const std::string filename, const cv::Mat& mat); bool saveMat(const std::string name, const std::string filename, const cv::Mat& mat);
bool loadMat(const std::string name, const std::string filename, cv::Mat& mat); bool loadMat(const std::string name, const std::string filename, cv::Mat& mat);


void getCheckerboardArea(std::vector<cv::Point2i>& pts);

// cv::Rect optimalRect;




public: public:
// apply on image
cv::Mat warp_matrix;

bool findOptimalProjectionArea(float ratio, cv_RectF& rect);




bool projMatorHomSet(){return projMatrixSet() || homOpenCVSet() || homSVDSet();} bool projMatorHomSet(){return projMatrixSet() || homOpenCVSet() || homSVDSet();}
Expand All @@ -106,9 +119,12 @@ class Projector_Calibrator {
bool warpMatrixSet(){ return warp_matrix.cols > 0;} bool warpMatrixSet(){ return warp_matrix.cols > 0;}




bool setupImageProjection(const cv_RectF& wall_area, const cv::Size& img_size);

bool setupImageProjection(float width_m, float height_m, float off_x_m, float off_y_m, const cv::Size& img_size); bool setupImageProjection(float width_m, float height_m, float off_x_m, float off_y_m, const cv::Size& img_size);
bool setupImageProjection(float width_m, float off_x_m, float off_y_m, const cv::Size& img_size); bool setupImageProjection(float width_m, float off_x_m, float off_y_m, const cv::Size& img_size);


bool imageProjectionSet() { return warp_matrix.cols > 0; }


// save 3d positions (in wall-frame) of the last checkerboard detection // save 3d positions (in wall-frame) of the last checkerboard detection
bool storeCurrent3DObservations(); bool storeCurrent3DObservations();
Expand Down Expand Up @@ -161,7 +177,7 @@ void showFullscreenCheckerboard();
Projector_Calibrator(){ Projector_Calibrator(){
kinect_orientation_valid = false; kinect_orientation_valid = false;
kinect_trafo_valid = false; kinect_trafo_valid = false;
C_checkboard_size = cv::Size(8,6); C_checkboard_size = cv::Size(10,8);
C_proj_size = cv::Size(1152,864); C_proj_size = cv::Size(1152,864);


projector_image = cv::Mat(C_proj_size, CV_8UC3); projector_image = cv::Mat(C_proj_size, CV_8UC3);
Expand Down
86 changes: 68 additions & 18 deletions src/main.cpp
Expand Up @@ -22,6 +22,7 @@
#include "user_input.h" #include "user_input.h"
#include "projector_calibrator.h" #include "projector_calibrator.h"


#include <stdlib.h>


ros::Publisher pub; ros::Publisher pub;
ros::Publisher pub_full_moved; ros::Publisher pub_full_moved;
Expand All @@ -40,9 +41,20 @@ Projector_Calibrator calibrator;
vector<float> measured_angles; vector<float> measured_angles;





float kinect_tilt_angle_deg = 0; float kinect_tilt_angle_deg = 0;
bool kinect_tilt_angle_valid = false; bool kinect_tilt_angle_valid = false;



// uncomment to show testImage, otherwise content of Main screen is shown on projector
//#define SHOW_TEST_IMAGE

#ifndef SHOW_TEST_IMAGE
cv::Size mainScreenSize(1920,1200);
cv_RectF optimalRect;
#endif


ros::Subscriber sub_imu; ros::Subscriber sub_imu;




Expand Down Expand Up @@ -85,9 +97,8 @@ void on_mouse_projector( int event, int x, int y, int flags, void* param ){






void callback(const ImageConstPtr& img_ptr, const sensor_msgs::PointCloud2ConstPtr& cloud_ptr){ void imgCB(const ImageConstPtr& img_ptr, const sensor_msgs::PointCloud2ConstPtr& cloud_ptr){


// ROS_INFO("callback");


// Kinect's orientation is needed to compute the transformation // Kinect's orientation is needed to compute the transformation
if (!calibrator.isKinectTrafoSet() && !calibrator.isKinectOrientationSet()){ if (!calibrator.isKinectTrafoSet() && !calibrator.isKinectOrientationSet()){
Expand Down Expand Up @@ -115,11 +126,11 @@ void callback(const ImageConstPtr& img_ptr, const sensor_msgs::PointCloud2ConstP
prog_state = GET_PROJECTION; prog_state = GET_PROJECTION;




if (prog_state == COLLECT_PATTERNS) // if (prog_state == COLLECT_PATTERNS)
cout << "State: COLLECT_PATTERNS" << endl; // cout << "State: COLLECT_PATTERNS" << endl;

//
if (prog_state == GET_PROJECTION) // if (prog_state == GET_PROJECTION)
cout << "State: GET_PROJECTION" << endl; // cout << "State: GET_PROJECTION" << endl;




// look for corners // look for corners
Expand Down Expand Up @@ -147,6 +158,13 @@ void callback(const ImageConstPtr& img_ptr, const sensor_msgs::PointCloud2ConstP
calibrator.setInputCloud(cloud); calibrator.setInputCloud(cloud);
calibrator.computeKinectTransformation(); calibrator.computeKinectTransformation();


#ifndef SHOW_TEST_IMAGE
optimalRect.width = 0;
if (!calibrator.findOptimalProjectionArea(mainScreenSize.width*1.0/mainScreenSize.height, optimalRect)){
ROS_ERROR("Could not find optimal Projection Area!");
}
#endif



prog_state = COLLECT_PATTERNS; prog_state = COLLECT_PATTERNS;
} }
Expand All @@ -156,13 +174,16 @@ void callback(const ImageConstPtr& img_ptr, const sensor_msgs::PointCloud2ConstP
// Cloud transformed_cloud; // Cloud transformed_cloud;
if (prog_state == COLLECT_PATTERNS){ if (prog_state == COLLECT_PATTERNS){





calibrator.storeCurrent3DObservations(); calibrator.storeCurrent3DObservations();


//if (!calibrator.homOpenCVSet()) //if (!calibrator.homOpenCVSet())
calibrator.computeHomography_SVD(); calibrator.computeHomography_SVD();


//if (!calibrator.homSVDSet()) //if (!calibrator.homSVDSet())
calibrator.computeHomography_OPENCV(); calibrator.computeHomography_OPENCV();


} }


Expand All @@ -186,19 +207,24 @@ void callback(const ImageConstPtr& img_ptr, const sensor_msgs::PointCloud2ConstP


if (!calibrator.warpMatrixSet()){ if (!calibrator.warpMatrixSet()){


#ifdef SHOW_TEST_IMAGE
float width = 0.8; float width = 0.8;
float height = width/calibrator.getTestImg()->cols*calibrator.getTestImg()->rows; // use ratio of input-image float height = width/calibrator.getTestImg()->cols*calibrator.getTestImg()->rows; // use ratio of input-image

float off_x = -width/2; float off_x = -width/2;
float off_y = -height/2; float off_y = -height/2;

calibrator.setupImageProjection(width,height, off_x, off_y, calibrator.getTestImg()->size()); calibrator.setupImageProjection(width,height, off_x, off_y, calibrator.getTestImg()->size());
#else
calibrator.setupImageProjection(optimalRect, mainScreenSize );
#endif

} }


#ifdef SHOW_TEST_IMAGE
if (calibrator.warpMatrixSet()){ if (calibrator.warpMatrixSet()){
calibrator.showUnWarpedImage(*calibrator.getTestImg()); calibrator.showUnWarpedImage(*calibrator.getTestImg());

} }
#endif

} }


if (calibrator.isKinectTrafoSet()){ if (calibrator.isKinectTrafoSet()){
Expand Down Expand Up @@ -236,12 +262,10 @@ void imu_CB(const sensor_msgs::ImuConstPtr& imu_ptr){
int main(int argc, char ** argv) int main(int argc, char ** argv)
{ {



ros::init(argc, argv, "subscriber"); ros::init(argc, argv, "subscriber");


//
// calibrator.initFromFile(); // calibrator.initFromFile();
//
// return 0;


ros::NodeHandle nh; ros::NodeHandle nh;
cv::namedWindow("camera", 1); cv::namedWindow("camera", 1);
Expand All @@ -260,12 +284,38 @@ int main(int argc, char ** argv)
message_filters::Subscriber<Image> image_sub(nh, "/camera/rgb/image_color", 2); message_filters::Subscriber<Image> image_sub(nh, "/camera/rgb/image_color", 2);
message_filters::Subscriber<PointCloud2> cloud_sub(nh, "/camera/rgb/points", 2); message_filters::Subscriber<PointCloud2> cloud_sub(nh, "/camera/rgb/points", 2);
Synchronizer<policy> sync(policy(2), image_sub, cloud_sub); Synchronizer<policy> sync(policy(2), image_sub, cloud_sub);
sync.registerCallback(boost::bind(&callback, _1, _2)); sync.registerCallback(boost::bind(&imgCB, _1, _2));




ros::Rate r(30);

while (ros::ok()){
ros::spinOnce();
r.sleep();


#ifndef SHOW_TEST_IMAGE

if (calibrator.imageProjectionSet()){

// cout << "warp " << endl << calibrator.warp_matrix << endl;
//
// ROS_INFO("Streaming");
system("xwd -root | convert - /tmp/screenshot.jpg");
cv::Mat screen = cv::imread("/tmp/screenshot.jpg");

cv::Mat primary_screen = screen(cv::Range(0,mainScreenSize.height), cv::Range(0,mainScreenSize.width));

calibrator.showUnWarpedImage(primary_screen);
}
#endif

}




ros::spin(); // ros::spin();
cvDestroyWindow("camera"); cv::destroyAllWindows();
return 0; return 0;


} }
Expand Down

0 comments on commit ab1a712

Please sign in to comment.