49 #include <opencv2/highgui/highgui.hpp> 50 #include "opencv2/imgproc/imgproc.hpp" 52 #include "opencv_apps/PyramidsConfig.h" 53 #include <dynamic_reconfigure/server.h> 66 typedef opencv_apps::PyramidsConfig
Config;
82 num_of_pyramids_ = config_.num_of_pyramids;
85 const std::string&
frameWithDefault(
const std::string& frame,
const std::string& image_frame)
92 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
94 doWork(msg, cam_info->header.frame_id);
99 doWork(msg, msg->header.frame_id);
102 void doWork(
const sensor_msgs::ImageConstPtr& image_msg,
const std::string& input_frame_from_msg)
112 switch (config_.pyramids_type)
114 case opencv_apps::Pyramids_Up:
119 cv::pyrUp(src_image, src_image, cv::Size(src_image.cols * 2, src_image.rows * 2));
123 case opencv_apps::Pyramids_Down:
128 cv::pyrDown(src_image, src_image, cv::Size(src_image.cols / 2, src_image.rows / 2));
137 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
138 cv::imshow(window_name_, src_image);
139 int c = cv::waitKey(1);
145 catch (cv::Exception& e)
147 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
154 if (config_.use_camera_info)
173 pnh_->param(
"queue_size", queue_size_, 3);
174 pnh_->param(
"debug_view", debug_view_,
false);
181 window_name_ =
"Image Pyramids Demo";
183 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
184 dynamic_reconfigure::Server<Config>::CallbackType
f =
186 reconfigure_server_->setCallback(f);
202 ROS_WARN(
"DeprecationWarning: Nodelet pyramids/pyramids is deprecated, " 203 "and renamed to opencv_apps/pyramids.");
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::CameraSubscriber cam_sub_
#define NODELET_ERROR(...)
dynamic_reconfigure::Server< Config > ReconfigureServer
opencv_apps::PyramidsConfig Config
void doWork(const sensor_msgs::ImageConstPtr &image_msg, const std::string &input_frame_from_msg)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
boost::shared_ptr< image_transport::ImageTransport > it_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void reconfigureCallback(Config &new_config, uint32_t level)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
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
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
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...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
PLUGINLIB_EXPORT_CLASS(opencv_apps::PyramidsNodelet, nodelet::Nodelet)
image_transport::Publisher img_pub_
image_transport::Subscriber img_sub_
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const