Go to the documentation of this file.
37 #ifndef JSK_PERCEPTION_DUAL_FISHEYE_TO_PANORAMA_H_
38 #define JSK_PERCEPTION_DUAL_FISHEYE_TO_PANORAMA_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include <sensor_msgs/Image.h>
42 #include <sensor_msgs/CameraInfo.h>
43 #include <jsk_recognition_msgs/PanoramaInfo.h>
49 #include <dynamic_reconfigure/server.h>
50 #include <jsk_perception/DualFisheyeConfig.h>
52 #include <opencv2/opencv.hpp>
60 class DualFisheyeToPanorama:
public jsk_topic_tools::DiagnosticNodelet
65 sensor_msgs::CameraInfo
67 typedef jsk_perception::DualFisheyeConfig
Config;
76 virtual void rectify(
const sensor_msgs::Image::ConstPtr& image_msg);
jsk_recognition_msgs::PanoramaInfo msg_panorama_info_
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)
image_transport::Publisher pub_panorama_image_
int blend_param_row_start_
image_transport::Subscriber sub_image_
std::string mls_map_path_
ros::Publisher pub_panorama_info_
virtual void unsubscribe()
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
bool sticher_initialized_
jsk_perception::DualFisheyeConfig Config
boost::shared_ptr< stitcher::FisheyeStitcher > stitcher_
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16