#include "ros/ros.h" #include #include #include #include #include #include #include using namespace cv; using namespace std; class Traite_image { public: const static int THRESHOLD_DETECT_SENSITIVITY = 10; const static int BLUR_SIZE = 5; const static int THRESHOLD_MOV = 5; constexpr static float MOVEMENT_THRES = 0.05; constexpr static float FLOW_MIN_QUAL = 0.01; const static int FLOW_MIN_DIST = 20; Mat prev; // Stabilisation transformation matrices Mat T, last_T; bool first = true; // Features vectors vector prev_ftr, cur_ftr; // Downsize factor int resize_f = 1; int theObject[2] = {0,0}; Rect objectBoundingRectangle = Rect(0,0,0,0); ros::NodeHandle n; image_transport::ImageTransport it; image_transport::Publisher pub_img; ros::Publisher pub_cmd; image_transport::Subscriber sub; Traite_image() : n("~"),it(n) { pub_img = it.advertise("/image_out", 1); pub_cmd = n.advertise("/vrep/drone/cmd_vel", 1); sub = it.subscribe("/usb_cam/image_raw", 1, [this](const sensor_msgs::ImageConstPtr& img) -> void { this->on_image(img);},ros::VoidPtr(),image_transport::TransportHints("compressed")); } // This processes an image and publishes the result. void on_image(const sensor_msgs::ImageConstPtr& msg) { cv_bridge::CvImageConstPtr bridge_input; try { bridge_input = cv_bridge::toCvShare(msg,sensor_msgs::image_encodings::RGB8); } catch (Exception& e) { std::ostringstream errstr; errstr << "cv_bridge exception caught: " << e.what(); return; } //Mat& input = const_cast(bridge_input->image); const Mat& input = bridge_input->image; Mat next; resize(input, next, Size(input.size().width/resize_f, input.size().height/resize_f)); Mat output;// = input.clone(); // (input.rows, input.cols, CV_32FC2); //ROS_INFO("got input"); if (first) { prev = next.clone(); first = false; ROS_INFO("first done"); } Mat next_stab; trackFeatures(prev, next); stabiliseImg(next, next_stab); trackingOptFlow(prev, next_stab, next_stab); Mat next_stab2; trackFeatures(prev, next); stabiliseImg(next, next_stab2); trackingOptFlow(prev, next_stab2, output); //searchForMovementOptFlow(prev_cropped, next_stab_cropped, output); pub_img.publish(cv_bridge::CvImage(msg->header, "rgb8", output).toImageMsg()); // bridge_input is handled by a smart-pointer. No explicit delete needed. droneTracking(Rect(Point(0,0), output.size())); //ROS_INFO("pub"); prev = next.clone(); } void trackFeatures(Mat prev, Mat cur) { Mat cur_grey, prev_grey; cvtColor(cur, cur_grey, COLOR_BGR2GRAY); cvtColor(prev, prev_grey, COLOR_BGR2GRAY); // vector from prev to cur vector prev_corner, cur_corner; vector status; vector err; goodFeaturesToTrack(prev_grey, prev_corner, 200, FLOW_MIN_QUAL, FLOW_MIN_DIST); calcOpticalFlowPyrLK(prev_grey, cur_grey, prev_corner, cur_corner, status, err); // weed out bad matches prev_ftr.resize(0); cur_ftr.resize(0); for(size_t i=0; i < status.size(); i++) { if(status[i]) { prev_ftr.push_back(prev_corner[i]); cur_ftr.push_back(cur_corner[i]); } } } void stabiliseImg(Mat cur, Mat &output){ T = estimateRigidTransform(prev_ftr, cur_ftr, true); // false = rigid transform, no scaling/shearing if(T.data == NULL) last_T.copyTo(T); else T.copyTo(last_T); Mat cur2; warpAffine(cur, cur2, T, cur.size(),INTER_NEAREST|WARP_INVERSE_MAP); cur2.copyTo(output); } void warpPoints(vector p, vector &p_warp, Mat T, bool invert=false) { Mat H; if(invert) invertAffineTransform(T, H); p_warp.clear(); for(size_t i=0; i < p.size(); ++i) { Mat src(3/*rows*/,1 /* cols */,CV_64F); src.at(0,0)=p[i].x; src.at(1,0)=p[i].y; src.at(2,0)=1.0; Mat dst = H*src; //USE MATRIX ALGEBRA p_warp.push_back(Point2f(dst.at(0,0),dst.at(1,0))); } } void trackingOptFlow(Mat prev, Mat cur, Mat &output) { cur.copyTo(output); vector cur_ftr_stab; //T = estimateRigidTransform(prev_ftr, cur_ftr, true); // false = rigid transform, no scaling/shearing //if(T.data == NULL) // last_T.copyTo(T); //else // T.copyTo(last_T); warpPoints(cur_ftr, cur_ftr_stab, T, true); vector objects; vector flow_norm; for(size_t i=0; i < prev_ftr.size(); ++i) { flow_norm.push_back(norm(prev_ftr[i] - cur_ftr_stab[i]) / prev.size().height); line(output, prev_ftr[i], cur_ftr[i], Scalar(200,0,0),1); line(output, prev_ftr[i], cur_ftr_stab[i], Scalar(0,200,0),1); } for(size_t i=0; i < flow_norm.size(); ++i) { if(flow_norm[i] > MOVEMENT_THRES) { objects.push_back(cur_ftr_stab[i]); prev_ftr.erase(prev_ftr.begin() + i); cur_ftr.erase(cur_ftr.begin() + i); } } for(size_t i=0; i < objects.size(); ++i) { circle(output, objects[i], 5, Scalar(0, 200, 0), 1); } } inline bool isFlowCorrect(Point2f u) { return !cvIsNaN(u.x) && !cvIsNaN(u.y) && fabs(u.x) < 1e9 && fabs(u.y) < 1e9; } void droneTracking(Rect img_size) { Point2f centre_image = Point2f(img_size.width/2, img_size.height/2); Point2f centre_rect = Point2f(objectBoundingRectangle.x + objectBoundingRectangle.width/2, objectBoundingRectangle.y + objectBoundingRectangle.height/2); geometry_msgs::Twist twist = geometry_msgs::Twist(); if(centre_rect.x < centre_image.x-THRESHOLD_MOV) { twist.angular.z = 0.2; } else if(centre_rect.x > centre_image.x+THRESHOLD_MOV) { twist.angular.z = -0.2; } pub_cmd.publish(twist); } //int to string helper function string intToString(int number){ //this function has a number input and string output std::stringstream ss; ss << number; return ss.str(); } }; int main(int argc, char **argv) { ros::init(argc, argv, "test_opencv"); Traite_image dataset=Traite_image(); ros::spin(); return 0; }