Code cleanup in progress

This commit is contained in:
lhark 2016-06-17 01:42:15 +02:00
parent 1d4447e29a
commit 41e1ec9f2e

View file

@ -13,7 +13,7 @@ using namespace std;
class Traite_image {
public:
const static int SENSITIVITY_VALUE = 20;
const static int BLUR_Size = 9;
const static int BLUR_SIZE = 9;
const static int CLOSE_SIZE = 30;
const static int ERODE_SIZE = 2;
const static int NB_FRAME_DROP = 1;
@ -29,10 +29,10 @@ class Traite_image {
ros::NodeHandle n;
image_transport::ImageTransport it;
image_transport::Subscriber sub;
image_transport::Publisher pub_img;
image_transport::Publisher pub_thres;
ros::Publisher pub_cmd;
image_transport::Subscriber sub;
Traite_image() : n("~"),it(n) {
@ -43,7 +43,8 @@ class Traite_image {
}
// This processes an image and publishes the result.
// Callback function executedwhen recieving an image from the camera
// Publishes to /papillon/image_out
void on_image(const sensor_msgs::ImageConstPtr& msg) {
cv_bridge::CvImageConstPtr bridge_input;
@ -118,11 +119,7 @@ class Traite_image {
}
T.copyTo(last_T);
cv::Mat cur2;
cv::warpAffine(cur, cur2, T, cur.size(),cv::INTER_CUBIC|cv::WARP_INVERSE_MAP);
cur2.copyTo(output);
cv::warpAffine(cur, output, T, cur.size(),cv::INTER_CUBIC|cv::WARP_INVERSE_MAP);
}
void searchForMovement(cv::Mat prev, cv::Mat cur, cv::Mat &output, cv::Mat &out2){
@ -130,8 +127,8 @@ class Traite_image {
cur.copyTo(output);
cv::cvtColor(prev, prev_grey, cv::COLOR_BGR2GRAY);
cv::cvtColor(cur, cur_grey, cv::COLOR_BGR2GRAY);
cv::GaussianBlur(prev_grey, prev_grey, cv::Size(BLUR_Size,BLUR_Size), 3.0);
cv::GaussianBlur(cur_grey, cur_grey, cv::Size(BLUR_Size,BLUR_Size), 3.0);
cv::GaussianBlur(prev_grey, prev_grey, cv::Size(BLUR_SIZE,BLUR_SIZE), 3.0);
cv::GaussianBlur(cur_grey, cur_grey, cv::Size(BLUR_SIZE,BLUR_SIZE), 3.0);
// Subtract the 2 last frames and threshold them
cv::Mat thres;