From 734817d97e9078045c7b4ae3bda49db239b283dc Mon Sep 17 00:00:00 2001 From: Yamato ANDO Date: Fri, 22 Dec 2017 14:05:57 +0900 Subject: [PATCH] even though the ID of the ADAS map does not start with #1, it has been modified to work properly --- .../packages/road_wizard/nodes/feat_proj/feat_proj.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ros/src/computing/perception/detection/packages/road_wizard/nodes/feat_proj/feat_proj.cpp b/ros/src/computing/perception/detection/packages/road_wizard/nodes/feat_proj/feat_proj.cpp index eae6278f942..bc4bc8c74be 100644 --- a/ros/src/computing/perception/detection/packages/road_wizard/nodes/feat_proj/feat_proj.cpp +++ b/ros/src/computing/perception/detection/packages/road_wizard/nodes/feat_proj/feat_proj.cpp @@ -309,9 +309,9 @@ void echoSignals2(ros::Publisher &pub, bool useOpenGLCoord = false) } } - for (unsigned int i = 1; i <= vmap.signals.size(); i++) + for (const auto& signal_map : vmap.signals) { - Signal signal = vmap.signals[i]; + const Signal signal = signal_map.second; int pid = vmap.vectors[signal.vid].pid; Point3 signalcenter = vmap.getPoint(pid);