Skip to content

Commit

Permalink
Merge pull request #95 from gcrowards/patch-1
Browse files Browse the repository at this point in the history
Improved variable names and comments
  • Loading branch information
k-okada authored Aug 7, 2019
2 parents 1192d8d + e56cd6f commit 3fb4842
Showing 1 changed file with 11 additions and 11 deletions.
22 changes: 11 additions & 11 deletions src/nodelet/simple_flow_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
static bool need_config_update_;
int scale_;

cv::Mat gray, prevGray;
cv::Mat color, prevColor;

void reconfigureCallback(Config& new_config, uint32_t level)
{
Expand Down Expand Up @@ -117,7 +117,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
// Convert the image into something opencv can handle.
cv::Mat frame_src = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;

/// Convert it to gray
/// Convert it to 3 channel
cv::Mat frame;
if (frame_src.channels() > 1)
{
Expand All @@ -128,18 +128,18 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
cv::cvtColor(frame_src, frame, cv::COLOR_GRAY2BGR);
}

cv::resize(frame, gray, cv::Size(frame.cols / (double)MAX(1, scale_), frame.rows / (double)MAX(1, scale_)), 0, 0,
cv::resize(frame, color, cv::Size(frame.cols / (double)MAX(1, scale_), frame.rows / (double)MAX(1, scale_)), 0, 0,
CV_INTER_AREA);
if (prevGray.empty())
gray.copyTo(prevGray);
if (prevColor.empty())
color.copyTo(prevColor);

if (gray.rows != prevGray.rows && gray.cols != prevGray.cols)
if (color.rows != prevColor.rows && color.cols != prevColor.cols)
{
NODELET_WARN("Images should be of equal sizes");
gray.copyTo(prevGray);
color.copyTo(prevColor);
}

if (frame.type() != 16)
if (frame.type() != CV_8UC3)
{
NODELET_ERROR("Images should be of equal type CV_8UC3");
}
Expand All @@ -164,9 +164,9 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet

float start = (float)cv::getTickCount();
#if CV_MAJOR_VERSION == 3
cv::optflow::calcOpticalFlowSF(gray, prevGray,
cv::optflow::calcOpticalFlowSF(color, prevColor,
#else
cv::calcOpticalFlowSF(gray, prevGray,
cv::calcOpticalFlowSF(color, prevColor,
#endif
flow, 3, 2, 4, 4.1, 25.5, 18, 55.0, 25.5, 0.35, 18, 55.0, 25.5, 10);
NODELET_INFO("calcOpticalFlowSF : %lf sec", (cv::getTickCount() - start) / cv::getTickFrequency());
Expand Down Expand Up @@ -210,7 +210,7 @@ class SimpleFlowNodelet : public opencv_apps::Nodelet
int c = cv::waitKey(1);
}

cv::swap(prevGray, gray);
cv::swap(prevColor, color);
// Publish the image.
sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", frame).toImageMsg();
img_pub_.publish(out_img);
Expand Down

0 comments on commit 3fb4842

Please sign in to comment.