log_polar_nodelet.h
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 
00003 #ifndef LOG_POLAR_NODELET_H_
00004 #define LOG_POLAR_NODELET_H_
00005 
00006 #include "resized_image_transport/image_processing_nodelet.h"
00007 #include "resized_image_transport/LogPolarConfig.h"
00008 
00009 namespace resized_image_transport
00010 {
00011   class LogPolar : public resized_image_transport::ImageProcessing
00012   {
00013   public:
00014   protected:
00015     typedef dynamic_reconfigure::Server<LogPolarConfig> ReconfigureServer;
00016     boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00017 
00018     bool inverse_log_polar_;
00019     double log_polar_scale_;
00020 
00021   protected:
00022     void onInit();
00023     void initReconfigure();
00024     void initParams();
00025     void config_cb (LogPolarConfig &config, uint32_t level);
00026     void process(const sensor_msgs::ImageConstPtr &src_img, const sensor_msgs::CameraInfoConstPtr &src_info,
00027                  sensor_msgs::ImagePtr &dst_img, sensor_msgs::CameraInfo &dst_info);
00028   };
00029 }
00030 #endif


resized_image_transport
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:41