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);
99 need_config_update_ =
true;
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);
126 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
127 if (need_config_update_)
129 reconfigure_server_->updateConfig(config_);
130 need_config_update_ =
false;
137 cv::createHanningWindow(hann, curr.size(), CV_64F);
140 prev.convertTo(prev64f, CV_64F);
141 curr.convertTo(curr64f, CV_64F);
143 cv::Point2d shift = cv::phaseCorrelate(prev64f, curr64f, hann);
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;
168 cv::imshow(window_name_, frame);
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);
184 prev_stamp_ = msg->header.stamp;
190 if (config_.use_camera_info)
209 pnh_->param(
"queue_size", queue_size_, 3);
210 pnh_->param(
"debug_view", debug_view_,
false);
217 window_name_ =
"phase shift";
219 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
220 dynamic_reconfigure::Server<Config>::CallbackType
f =
222 reconfigure_server_->setCallback(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.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static bool need_config_update_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
static void trackbarCallback(int, void *)
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
opencv_apps::PhaseCorrConfig Config
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Demo code to calculate moments.
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
image_transport::CameraSubscriber cam_sub_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
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...
boost::shared_ptr< image_transport::ImageTransport > it_
void publish(const sensor_msgs::Image &message) const
image_transport::Subscriber img_sub_
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
boost::shared_ptr< ReconfigureServer > reconfigure_server_
image_transport::Publisher img_pub_
void reconfigureCallback(Config &new_config, uint32_t level)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
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...
PLUGINLIB_EXPORT_CLASS(opencv_apps::PhaseCorrNodelet, nodelet::Nodelet)
dynamic_reconfigure::Server< Config > ReconfigureServer
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const