37 #ifndef JSK_PERCEPTION_FISHEYE_TO_PANORAMA_H_ 38 #define JSK_PERCEPTION_FISHEYE_TO_PANORAMA_H_ 41 #include <sensor_msgs/Image.h> 42 #include <sensor_msgs/CameraInfo.h> 48 #include <dynamic_reconfigure/server.h> 49 #include <jsk_perception/FisheyeConfig.h> 51 #include <opencv2/opencv.hpp> 60 sensor_msgs::CameraInfo
62 typedef jsk_perception::FisheyeConfig
Config;
71 inline double interpolate(
double rate,
double first,
double second){
return (1.0 - rate) * first + rate * second;};
72 virtual void rectify(
const sensor_msgs::Image::ConstPtr& image_msg);
jsk_perception::FisheyeConfig Config
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
virtual void rectify(const sensor_msgs::Image::ConstPtr &image_msg)
ros::Publisher pub_undistorted_bilinear_image_
ros::Publisher pub_undistorted_image_
ros::Subscriber sub_image_
double interpolate(double rate, double first, double second)
virtual void unsubscribe()
void configCallback(Config &new_config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_