37 #ifndef JSK_PERCEPTION_DUAL_FISHEYE_TO_PANORAMA_H_ 38 #define JSK_PERCEPTION_DUAL_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/DualFisheyeConfig.h> 51 #include <opencv2/opencv.hpp> 63 sensor_msgs::CameraInfo
65 typedef jsk_perception::DualFisheyeConfig
Config;
74 virtual void rectify(
const sensor_msgs::Image::ConstPtr& image_msg);
std::string mls_map_path_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
virtual void unsubscribe()
bool sticher_initialized_
boost::shared_ptr< stitcher::FisheyeStitcher > stitcher_
jsk_perception::DualFisheyeConfig Config
ros::Subscriber sub_image_
virtual void rectify(const sensor_msgs::Image::ConstPtr &image_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void configCallback(Config &new_config, uint32_t level)
ros::Publisher pub_panorama_image_