46 #include <opencv2/highgui/highgui.hpp> 47 #include <opencv2/imgproc/imgproc.hpp> 48 #include <opencv2/video/tracking.hpp> 49 #if CV_MAJOR_VERSION == 3 50 #include <opencv2/optflow.hpp> 53 #include <dynamic_reconfigure/server.h> 54 #include "opencv_apps/SimpleFlowConfig.h" 55 #include "opencv_apps/FlowArrayStamped.h" 68 typedef opencv_apps::SimpleFlowConfig
Config;
87 scale_ = config_.scale;
90 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
97 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
99 doWork(msg, cam_info->header.frame_id);
104 doWork(msg, msg->header.frame_id);
109 need_config_update_ =
true;
112 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
122 if (frame_src.channels() > 1)
128 cv::cvtColor(frame_src, frame, cv::COLOR_GRAY2BGR);
131 cv::resize(frame, gray, cv::Size(frame.cols / (
double)MAX(1, scale_), frame.rows / (
double)MAX(1, scale_)), 0, 0,
133 if (prevGray.empty())
134 gray.copyTo(prevGray);
136 if (gray.rows != prevGray.rows && gray.cols != prevGray.cols)
139 gray.copyTo(prevGray);
142 if (frame.type() != 16)
147 opencv_apps::FlowArrayStamped flows_msg;
148 flows_msg.header = msg->header;
155 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
157 if (need_config_update_)
160 reconfigure_server_->updateConfig(config_);
161 need_config_update_ =
false;
165 float start = (float)cv::getTickCount();
166 #if CV_MAJOR_VERSION == 3 167 cv::optflow::calcOpticalFlowSF(gray, prevGray,
169 cv::calcOpticalFlowSF(gray, prevGray,
171 flow, 3, 2, 4, 4.1, 25.5, 18, 55.0, 25.5, 0.35, 18, 55.0, 25.5, 10);
172 NODELET_INFO(
"calcOpticalFlowSF : %lf sec", (cv::getTickCount() - start) / cv::getTickFrequency());
175 int cols = flow.cols;
176 int rows = flow.rows;
177 double scale_col = frame.cols / (double)flow.cols;
178 double scale_row = frame.rows / (
double)flow.rows;
180 for (
int i = 0; i < rows; ++i)
182 for (
int j = 0; j < cols; ++j)
184 cv::Vec2f flow_at_point = flow.at<cv::Vec2f>(i, j);
185 cv::line(frame, cv::Point(scale_col * j, scale_row * i),
186 cv::Point(scale_col * (j + flow_at_point[0]), scale_row * (i + flow_at_point[1])),
187 cv::Scalar(0, 255, 0), 1, 8, 0);
189 opencv_apps::Flow flow_msg;
190 opencv_apps::Point2D point_msg;
191 opencv_apps::Point2D velocity_msg;
192 point_msg.x = scale_col * j;
193 point_msg.y = scale_row * i;
194 velocity_msg.x = scale_col * flow_at_point[0];
195 velocity_msg.y = scale_row * flow_at_point[1];
196 flow_msg.point = point_msg;
197 flow_msg.velocity = velocity_msg;
198 flows_msg.flow.push_back(flow_msg);
209 cv::imshow(window_name_, frame);
210 int c = cv::waitKey(1);
213 cv::swap(prevGray, gray);
219 catch (cv::Exception& e)
221 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
224 prev_stamp_ = msg->header.stamp;
230 if (config_.use_camera_info)
249 pnh_->param(
"queue_size", queue_size_, 3);
250 pnh_->param(
"debug_view", debug_view_,
false);
257 window_name_ =
"simpleflow_demo";
260 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
261 dynamic_reconfigure::Server<Config>::CallbackType
f =
263 reconfigure_server_->setCallback(f);
266 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*
pnh_,
"flows", 1);
281 ROS_WARN(
"DeprecationWarning: Nodelet simple_flow/simple_flow is deprecated, " 282 "and renamed to opencv_apps/simple_flow.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
image_transport::Publisher img_pub_
void publish(const boost::shared_ptr< M > &message) const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
opencv_apps::SimpleFlowConfig Config
PLUGINLIB_EXPORT_CLASS(opencv_apps::SimpleFlowNodelet, nodelet::Nodelet)
void reconfigureCallback(Config &new_config, uint32_t level)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
static bool need_config_update_
image_transport::CameraSubscriber cam_sub_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void publish(const sensor_msgs::Image &message) const
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< ReconfigureServer > reconfigure_server_
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< image_transport::ImageTransport > it_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
#define NODELET_INFO(...)
image_transport::Subscriber img_sub_
static void trackbarCallback(int, void *)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const