Skip to content

Commit 8fd2d65

Browse files
sktometometok-okada
authored andcommitted
Revert "[jsk_perception] change dual_fisheye_to_panorama to use sensor_msgs/PanoramaInfo"
This reverts commit 6fd5dae , until ros/common_msgs#171 has merged
1 parent e62e4a2 commit 8fd2d65

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

jsk_perception/include/jsk_perception/dual_fisheye_to_panorama.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
#include <jsk_topic_tools/diagnostic_nodelet.h>
4141
#include <sensor_msgs/Image.h>
4242
#include <sensor_msgs/CameraInfo.h>
43-
#include <sensor_msgs/PanoramaInfo.h>
43+
#include <jsk_recognition_msgs/PanoramaInfo.h>
4444

4545
#include <message_filters/subscriber.h>
4646
#include <message_filters/synchronizer.h>
@@ -80,7 +80,7 @@ namespace jsk_perception
8080
ros::Publisher pub_panorama_image_;
8181
ros::Publisher pub_panorama_info_;
8282

83-
sensor_msgs::PanoramaInfo msg_panorama_info_;
83+
jsk_recognition_msgs::PanoramaInfo msg_panorama_info_;
8484

8585
bool enb_lc_;
8686
bool enb_ra_;

jsk_perception/src/dual_fisheye_to_panorama.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@
3838
#include <cv_bridge/cv_bridge.h>
3939
#include <sensor_msgs/Image.h>
4040
#include <sensor_msgs/image_encodings.h>
41-
#include <sensor_msgs/PanoramaInfo.h>
41+
#include <jsk_recognition_msgs/PanoramaInfo.h>
4242
#include <algorithm>
4343
#include <math.h>
4444
#include <boost/assign.hpp>
@@ -61,7 +61,7 @@ namespace jsk_perception
6161
ROS_INFO("save_unwarped: %7.3f", save_unwarped_?"true":"false");
6262
ROS_INFO("mls_map_path : %s", mls_map_path_.c_str());
6363
pub_panorama_image_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
64-
pub_panorama_info_ = advertise<sensor_msgs::PanoramaInfo>(*pnh_, "panorama_info", 1);
64+
pub_panorama_info_ = advertise<jsk_recognition_msgs::PanoramaInfo>(*pnh_, "panorama_info", 1);
6565

6666
sticher_initialized_ = false;
6767
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);

0 commit comments

Comments
 (0)