From f0fda74857150ea9074e37051f343f48a5193ccf Mon Sep 17 00:00:00 2001 From: syouji Date: Thu, 3 Dec 2015 19:41:13 +0900 Subject: [PATCH] Stop publishing messages of lane namespace --- .../vector_map_query/vector_map_query.cpp | 56 ++++++++++--------- .../vector_map_loader/vector_map_loader.cpp | 56 ++++++++++--------- 2 files changed, 60 insertions(+), 52 deletions(-) diff --git a/ros/src/data/packages/map_db/nodes/vector_map_query/vector_map_query.cpp b/ros/src/data/packages/map_db/nodes/vector_map_query/vector_map_query.cpp index 33c813e0dd4..91dc813b2e6 100644 --- a/ros/src/data/packages/map_db/nodes/vector_map_query/vector_map_query.cpp +++ b/ros/src/data/packages/map_db/nodes/vector_map_query/vector_map_query.cpp @@ -683,6 +683,8 @@ rosrun map_file vector_map_loader ros::init(argc, argv, "sample_vector_map"); ros::NodeHandle n; + bool publish_lane; + n.param("/sample_vector_map/publish_lane", publish_lane, false); ros::Publisher pub = n.advertise("/vector_map", 1000, true); ros::Publisher stat_publisher = n.advertise("/vmap_stat", 100);; std_msgs::Bool vmap_stat_msg; @@ -951,36 +953,38 @@ rosrun map_file vector_map_loader marker.id = 0; // road data - if(lanes.size() > 0 && dtlanes.size() <= 0) { - std::cerr << "error: dtlane.csv is not loaded.\n" - << "\tlane.csv needs dtlane.csv" - << std::endl; - std::exit(1); - } - marker.ns = "lane"; - for (i=0; i 0 && dtlanes.size() <= 0) { + std::cerr << "error: dtlane.csv is not loaded.\n" + << "\tlane.csv needs dtlane.csv" + << std::endl; + std::exit(1); } - int did = lanes[i].did; - int pid = dtlanes[did].pid; - double ox, oy, oz, ow; + marker.ns = "lane"; + for (i=0; i ros::init(argc, argv, "sample_vector_map"); ros::NodeHandle n; + bool publish_lane; + n.param("/sample_vector_map/publish_lane", publish_lane, false); ros::Publisher pub = n.advertise("/vector_map", 1000, true); ros::Publisher stat_publisher = n.advertise("/vmap_stat", 100);; std_msgs::Bool vmap_stat_msg; @@ -987,36 +989,38 @@ rosrun map_file vector_map_loader marker.id = 0; // road data - if(lanes.size() > 0 && dtlanes.size() <= 0) { - std::cerr << "error: dtlane.csv is not loaded.\n" - << "\tlane.csv needs dtlane.csv" - << std::endl; - std::exit(1); - } - marker.ns = "lane"; - for (i=0; i 0 && dtlanes.size() <= 0) { + std::cerr << "error: dtlane.csv is not loaded.\n" + << "\tlane.csv needs dtlane.csv" + << std::endl; + std::exit(1); } - int did = lanes[i].did; - int pid = dtlanes[did].pid; - double ox, oy, oz, ow; + marker.ns = "lane"; + for (i=0; i