43 #include <opencv2/highgui/highgui.hpp>
44 #include <opencv2/imgproc/imgproc.hpp>
46 #include <dynamic_reconfigure/server.h>
47 #include "opencv_apps/PhaseCorrConfig.h"
48 #include "opencv_apps/Point2DStamped.h"
61 typedef opencv_apps::PhaseCorrConfig
Config;
80 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
87 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
89 doWork(msg, cam_info->header.frame_id);
94 doWork(msg, msg->header.frame_id);
102 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
111 opencv_apps::Point2DStamped shift_msg;
112 shift_msg.header = msg->header;
115 if (frame.channels() > 1)
117 cv::cvtColor(frame,
curr, cv::COLOR_BGR2GRAY);
137 cv::createHanningWindow(
hann,
curr.size(), CV_64F);
144 double radius = cv::sqrt(shift.x * shift.x + shift.y * shift.y);
149 cv::Point center(
curr.cols >> 1,
curr.rows >> 1);
150 #ifndef CV_VERSION_EPOCH
151 cv::circle(frame, center, (
int)(radius * 5), cv::Scalar(0, 255, 0), 3, cv::LINE_AA);
152 cv::line(frame, center, cv::Point(center.x + (
int)(shift.x * 5), center.y + (
int)(shift.y * 5)),
153 cv::Scalar(0, 255, 0), 3, cv::LINE_AA);
155 cv::circle(frame, center, (
int)(radius * 5), cv::Scalar(0, 255, 0), 3, CV_AA);
156 cv::line(frame, center, cv::Point(center.x + (
int)(shift.x * 5), center.y + (
int)(shift.y * 5)),
157 cv::Scalar(0, 255, 0), 3, CV_AA);
161 shift_msg.point.x = shift.x;
162 shift_msg.point.y = shift.y;
169 int c = cv::waitKey(1);
179 catch (cv::Exception& e)
181 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
220 dynamic_reconfigure::Server<Config>::CallbackType
f =
225 msg_pub_ = advertise<opencv_apps::Point2DStamped>(*
pnh_,
"shift", 1);
240 ROS_WARN(
"DeprecationWarning: Nodelet phase_corr/phase_corr is deprecated, "
241 "and renamed to opencv_apps/phase_corr.");
247 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H