39 #include <sensor_msgs/Image.h> 43 #include <boost/assign.hpp> 51 DiagnosticNodelet::onInit();
65 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
66 dynamic_reconfigure::Server<Config>::CallbackType
f =
68 srv_->setCallback (f);
94 cv::resize(
cv_bridge::toCvCopy(image_msg, image_msg->encoding)->image, img, cv::Size(3840,1920));
97 ROS_INFO(
"initialize stitcher w:%d h:%d", img.size().width, img.size().height);
107 cv::Mat img_l, img_r;
109 img_l =
img(cv::Rect(0, 0,
110 static_cast<int>(img.size().width / 2), img.size().height));
112 img_r =
img(cv::Rect(static_cast<int>(img.size().width / 2), 0,
113 static_cast<int>(img.size().width / 2), img.size().height));
std::string mls_map_path_
void publish(const boost::shared_ptr< M > &message) const
virtual void unsubscribe()
bool sticher_initialized_
boost::shared_ptr< stitcher::FisheyeStitcher > stitcher_
jsk_perception::DualFisheyeConfig Config
std::vector< std::string > V_string
ros::Subscriber sub_image_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void rectify(const sensor_msgs::Image::ConstPtr &image_msg)
PLUGINLIB_EXPORT_CLASS(jsk_perception::DualFisheyeToPanorama, nodelet::Nodelet)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
sensor_msgs::ImagePtr toImageMsg() const
void configCallback(Config &new_config, uint32_t level)
ros::Publisher pub_panorama_image_