Go to the documentation of this file.
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;
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)
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));
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);
184 dynamic_reconfigure::Server<Config>::CallbackType
f =
202 ROS_WARN(
"DeprecationWarning: Nodelet pyramids/pyramids is deprecated, "
203 "and renamed to opencv_apps/pyramids.");
209 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
image_transport::Publisher img_pub_
#define NODELET_ERROR(...)
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
sensor_msgs::ImagePtr toImageMsg() const
void reconfigureCallback(Config &new_config, uint32_t level)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
opencv_apps::PyramidsConfig Config
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
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....
dynamic_reconfigure::Server< Config > ReconfigureServer
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
image_transport::Subscriber img_sub_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
boost::shared_ptr< image_transport::ImageTransport > it_
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
void publish(const sensor_msgs::Image &message) const
Demo code to calculate moments.
image_transport::CameraSubscriber cam_sub_
void doWork(const sensor_msgs::ImageConstPtr &image_msg, const std::string &input_frame_from_msg)
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
const std::string & frameWithDefault(const std::string &frame, const std::string &image_frame)
PLUGINLIB_EXPORT_CLASS(opencv_apps::PyramidsNodelet, nodelet::Nodelet)
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
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.
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
#define NODELET_DEBUG(...)
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49