diff --git a/modules/perception/obstacle/camera/visualizer/camera_visualizer.cc b/modules/perception/obstacle/camera/visualizer/camera_visualizer.cc index 691aeae41def0f119517883b3041c16099b6f5e8..16c63369eed83575b33c80ec5f1b8f286c62e0c7 100644 --- a/modules/perception/obstacle/camera/visualizer/camera_visualizer.cc +++ b/modules/perception/obstacle/camera/visualizer/camera_visualizer.cc @@ -35,11 +35,10 @@ std::map kColorTable = { {std::string("debug_roi"), cv::Scalar(255, 169, 255)}}; std::vector> g_cached_images; -const int kMaxCachedImageNum = 100; +const int kMaxCachedImageNum = 10; void OnPerception(const PerceptionObstacles &); void OnImageShort(const sensor_msgs::ImagePtr &); -void OnImageLong(const sensor_msgs::ImagePtr &); int main(int argc, char **argv) { ros::init(argc, argv, "camera_visualizer"); @@ -47,8 +46,6 @@ int main(int argc, char **argv) { ros::Subscriber sub_perception_debug = n.subscribe(FLAGS_perception_obstacle_topic, 1000, OnPerception); - ros::Subscriber sub_tl_image_long = - n.subscribe(FLAGS_image_long_topic, 1000, OnImageLong); ros::Subscriber sub_tl_image_short = n.subscribe(FLAGS_image_short_topic, 1000, OnImageShort); @@ -80,9 +77,6 @@ void OnImage(CameraId camera_id, const sensor_msgs::ImagePtr &msg) { g_cached_images.erase(g_cached_images.begin()); } } -void OnImageLong(const sensor_msgs::ImagePtr &msg) { - OnImage(CameraId::LONG_FOCUS, msg); -} void OnImageShort(const sensor_msgs::ImagePtr &msg) { OnImage(CameraId::SHORT_FOCUS, msg);