diff --git a/jsk_perception/include/jsk_perception/dual_fisheye_to_panorama.h b/jsk_perception/include/jsk_perception/dual_fisheye_to_panorama.h index 575b0f559f..c6fbbbdbb4 100644 --- a/jsk_perception/include/jsk_perception/dual_fisheye_to_panorama.h +++ b/jsk_perception/include/jsk_perception/dual_fisheye_to_panorama.h @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include #include @@ -80,7 +80,7 @@ namespace jsk_perception ros::Publisher pub_panorama_image_; ros::Publisher pub_panorama_info_; - sensor_msgs::PanoramaInfo msg_panorama_info_; + jsk_recognition_msgs::PanoramaInfo msg_panorama_info_; bool enb_lc_; bool enb_ra_; diff --git a/jsk_perception/src/dual_fisheye_to_panorama.cpp b/jsk_perception/src/dual_fisheye_to_panorama.cpp index 72eb1afbf7..9473f988e1 100644 --- a/jsk_perception/src/dual_fisheye_to_panorama.cpp +++ b/jsk_perception/src/dual_fisheye_to_panorama.cpp @@ -38,7 +38,7 @@ #include #include #include -#include +#include #include #include #include @@ -61,7 +61,7 @@ namespace jsk_perception ROS_INFO("save_unwarped: %7.3f", save_unwarped_?"true":"false"); ROS_INFO("mls_map_path : %s", mls_map_path_.c_str()); pub_panorama_image_ = advertise(*pnh_, "output", 1); - pub_panorama_info_ = advertise(*pnh_, "panorama_info", 1); + pub_panorama_info_ = advertise(*pnh_, "panorama_info", 1); sticher_initialized_ = false; srv_ = boost::make_shared > (*pnh_);